copied everything over from 2012 and removed all of the actual robot code except the drivetrain stuff
git-svn-id: https://robotics.mvla.net/svn/frc971/2013/trunk/src@4078 f308d9b7-e957-4cde-b6ac-9a88185e7312
diff --git a/aos/README.txt b/aos/README.txt
new file mode 100644
index 0000000..00762f3
--- /dev/null
+++ b/aos/README.txt
@@ -0,0 +1,35 @@
+see ../README.txt for overall information
+
+[FILES]
+config/ has some configuration files
+ aos.conf has directions for setting up resource limits so you can run the code on any linux machine (the directions are there to keep them with the file)
+ setup_rc_caps.sh is a shell script (you have to run as root) that lets you run the realtime code without installing aos.conf for an individual file
+ starter is an init.d file
+ install it by putting it in /etc/init.d an running "update-rc.d starter defaults"
+ restart it by running "invoke-rc.d starter restart" (doesn't always work very well...)
+ the .config files are for building linux kernels
+
+atom_code/ has code that only runs on the atom
+crio/ has code that only runs on the crio
+
+common/ is where stuff that runs on both the crio and the atom is
+common/input/ is where the framework code for reading stuff into the queues system is
+common/output/ is where the framework for writing things out of the queues system is
+common/messages is where the c++ wrappers for "queues" are
+
+[NOTES]
+C++ code should _only_ #include "aos/aos_core.h" because it has the extern "C" stuff etc. That should have all of the necessary header files #included, but if it doesn't, they should get added.
+Some functions need to be in separate translation units in order for them to be guaranteed to work. As the C standard says,
+ Alternatively, an implementation might perform various optimizations within each translation unit, such
+ that the actual semantics would agree with the abstract semantics only when making function calls across
+ translation unit boundaries. In such an implementation, at the time of each function entry and function
+ return where the calling function and the called function are in different translation units, the values of all
+ externally linked objects and of all objects accessible via pointers therein would agree with the abstract
+ semantics. Furthermore, at the time of each such function entry the values of the parameters of the called
+ function and of all objects accessible via pointers therein would agree with the abstract semantics. In this
+ type of implementation, objects referred to by interrupt service routines activated by the signal function
+ would require explicit specification of volatile storage, as well as other implementation-defined
+ restrictions.
+Everything that has to do different things when compiled for the crio or the atom uses #ifdef __VXWORKS__ etc.
+The crio "queue" implementation uses 1 global instance and no synchronization, so it should only be used in code that gets called by the crio-side control loop infrastructure.
+The C++ namespace aos is used for all of the aos code. The crio and atom namespaces are for APIs that only make sense on one platform or the other.
diff --git a/aos/aos.swig b/aos/aos.swig
new file mode 100644
index 0000000..fee0700
--- /dev/null
+++ b/aos/aos.swig
@@ -0,0 +1,45 @@
+%module aos
+
+%include "std_string.i";
+%include "stdint.i";
+
+%{
+#include <time.h>
+#include "aos/common/time.h"
+#include "aos/common/queue.h"
+static_assert(sizeof(int) == sizeof(clockid_t),
+ "Sizeof clockid_t has changed.");
+%}
+
+%apply int { clockid_t };
+
+// Makes the constructors from c++ types public so that this code can be called
+// from other places.
+%typemap(javabody) SWIGTYPE %{
+ private long swigCPtr;
+ protected boolean swigCMemOwn;
+
+ public $javaclassname(long cPtr, boolean cMemoryOwn) {
+ swigCMemOwn = cMemoryOwn;
+ swigCPtr = cPtr;
+ }
+
+ public static long getCPtr($javaclassname obj) {
+ return (obj == null) ? 0 : obj.swigCPtr;
+ }
+%}
+
+%rename(add) operator+;
+%rename(subtract) operator-;
+%rename(multiply) operator*;
+%rename(divide) operator/;
+%rename(modulo) operator%;
+%rename(equalTo) operator==;
+%rename(notEqual) operator!=;
+%rename(greaterThan) operator>;
+%rename(lessThan) operator<;
+%rename(leq) operator<=;
+%rename(geq) operator>=;
+
+%include "aos/common/time.h"
+%include "aos/common/queue.h"
diff --git a/aos/aos_core.h b/aos/aos_core.h
new file mode 100644
index 0000000..13a427e
--- /dev/null
+++ b/aos/aos_core.h
@@ -0,0 +1,81 @@
+#ifndef _AOS_CORE_H_
+#define _AOS_CORE_H_
+
+#ifdef __VXWORKS__
+#include "WPILib/Task.h"
+#endif
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef __VXWORKS__
+#include "aos/atom_code/ipc_lib/resource.h"
+#include "aos/atom_code/ipc_lib/shared_mem.h"
+#include "aos/atom_code/ipc_lib/queue.h"
+#ifdef __cplusplus
+}
+#include "aos/atom_code/init.h"
+extern "C" {
+#endif
+
+// A macro that runs a control loop using AOS_RUN on linux, and lets the user
+// register the control loop on the cRIO.
+#define AOS_RUN_LOOP AOS_RUN
+
+// A macro that will create an instance of the given class using
+// its default constructor and call Run() on it on the cRIO or the atom.
+// It will generate a main on the atom and a function that the build system links
+// in a call to on the cRIO.
+// NOTE: No ; after this macro, and it should be used at the file scope (NO NAMESPACES!).
+#define AOS_RUN(classname) int main() { \
+ aos::Init(); \
+ classname looper; /* on the stack to avoid eigen alignment issue */ \
+ looper.Run(); \
+ aos::Cleanup(); \
+}
+// Same as AOS_RUN, except uses aos::init_nrt instead of aos::init.
+#define AOS_RUN_NRT(classname) int main() { \
+ aos::InitNRT(); \
+ classname looper; /* on the stack to avoid eigen alignment issue */ \
+ looper.Run(); \
+ aos::Cleanup(); \
+}
+// Same as AOS_RUN, except passes args to the constructor.
+#define AOS_RUN_ARGS(classname, args...) int () { \
+ aos::Init(); \
+ classname looper(args); /* on the stack to avoid eigen alignment issue */ \
+ looper.Run(); \
+ aos::Cleanup(); \
+}
+
+#else // ifndef __VXWORKS__
+
+// The cRIO doesn't need to run the Run method. The cRIO main should register
+// all loops to get run.
+#define AOS_RUN_LOOP(classname) /* nop */
+
+#define AOS_RUN(classname) extern "C" void AOS_INITNAME() { \
+ classname *looper = new classname(); /* dynamically allocated because most (all?) Run functions store references */ \
+ looper->Run(); \
+}
+// Same as AOS_RUN, except it runs in a new Task (named name and at priority).
+// Calls both the constructor and Run in the new Task.
+#define AOS_RUN_FORK(classname, name, priority) \
+static void aos_init_(void *) { \
+ classname *looper = new classname(); /* dynamically allocated because most (all?) Run functions store references */ \
+ looper->Run(); \
+} \
+extern "C" void AOS_INITNAME() { \
+ (new Task(name, reinterpret_cast<FUNCPTR>(aos_init_), priority))->Start(); \
+}
+
+#endif // ifndef __VXWORKS__
+
+#ifdef __cplusplus
+}
+#endif
+
+#include "aos/common/logging/logging.h"
+
+#endif
diff --git a/aos/aos_stdint.h b/aos/aos_stdint.h
new file mode 100644
index 0000000..accb5ce
--- /dev/null
+++ b/aos/aos_stdint.h
@@ -0,0 +1,12 @@
+#ifndef AOS_AOS_STDINT_H_
+#define AOS_AOS_STDINT_H_
+
+#include <stdint.h>
+
+#ifdef __VXWORKS__
+typedef int64_t intmax_t;
+typedef uint64_t uintmax_t;
+#endif
+
+#endif
+
diff --git a/aos/atom_code/README.txt b/aos/atom_code/README.txt
new file mode 100644
index 0000000..5cf8182
--- /dev/null
+++ b/aos/atom_code/README.txt
@@ -0,0 +1,6 @@
+see ../README.txt for stuff affecting crio and atom code
+
+[NOTES]
+Any code should call aos::Init() (or aos::InitNRT() for processes that don't need to be realtime) before making any calls to any of the aos functions.
+Making calls to any of the aos functions (including aos::Init()) from more than 1 thread per process is not supported, but using fork(2) after some aos functions have been called and then continuing to make aos function calls (without calling one of the exec(3) functions) in both processes is supported.
+
diff --git a/aos/atom_code/async_action/AsyncAction.cpp.inc b/aos/atom_code/async_action/AsyncAction.cpp.inc
new file mode 100644
index 0000000..911bee8
--- /dev/null
+++ b/aos/atom_code/async_action/AsyncAction.cpp.inc
@@ -0,0 +1,405 @@
+#include <sys/syscall.h>
+#include <errno.h>
+#include <math.h>
+
+namespace aos {
+
+template<class T, class S> AsyncAction<T, S>::AsyncAction(const std::string name) : local_count(0), local_done_status(0), local_pid(0),
+ done_index(0), status_index(0), next_status_count(0){
+ aos_type_sig async_action_status_sig = {sizeof(async_action_status<S>), 1234, 1};
+ status_queue = aos_fetch_queue(name.c_str(), &async_action_status_sig);
+ aos_type_sig async_action_start_sig = {sizeof(async_action_start<T>), 4321, 1};
+ start_queue = aos_fetch_queue(name.c_str(), &async_action_start_sig);
+}
+
+template<class T, class S> uint16_t AsyncAction<T, S>::Start(T &args){
+ CheckStop();
+ // write something to the start queue and increment the count in the status queue
+ async_action_start<S> *start = (async_action_start<S> *)aos_queue_get_msg(start_queue);
+ if(start == NULL)
+ return 0;
+ memcpy(&start->args, &args, sizeof(T));
+ async_action_status<T> *status = (async_action_status<T> *)aos_queue_read_msg(status_queue, 0); // wait until one starts it if didn't already
+ uint16_t r = 0;
+ aos_resource_entity *entity;
+ if(status == NULL)
+ goto err;
+ r = status->count + 1;
+ local_pid = status->pid;
+ start->count = r;
+ entity = status->resource_entity;
+ aos_queue_free_msg(status_queue, status);
+ status = (async_action_status<T> *)aos_queue_get_msg(status_queue);
+ status->count = r;
+ status->done_status = 0;
+ status->pid = local_pid;
+ status->resource_entity = entity; // the resource_entity of the action, not the caller!
+ start->parent = resource_entity; // if it's NULL, it'll get fixed when starting
+ if(aos_queue_write_msg(status_queue, status, OVERRIDE) < 0){
+ goto err;
+ } else {
+ status = NULL;
+ }
+ if(aos_queue_write_msg(start_queue, start, OVERRIDE) < 0){
+ goto err;
+ } else {
+ start = NULL;
+ }
+err:
+ if(start != NULL)
+ aos_queue_free_msg(start_queue, start);
+ if(status != NULL)
+ aos_queue_free_msg(status_queue, status);
+ local_count = r;
+ return r;
+}
+template<class T, class S> void AsyncAction<T, S>::Stop(int32_t count){
+ CheckStop();
+ async_action_status<S> *status = (async_action_status<S> *)aos_queue_read_msg(status_queue, PEEK | NON_BLOCK);
+ if(status == NULL)
+ return;
+ local_pid = status->pid;
+ local_count = status->count;
+ aos_queue_free_msg(status_queue, status);
+ if(local_count != GetCount(count)) // if it's the wrong one
+ return;
+ async_action_start<S> *start = (async_action_start<S> *)aos_queue_read_msg(start_queue, PEEK | NON_BLOCK);
+ if(start == NULL) // if there isn't something in the start queue (aka one running)
+ return;
+ aos_queue_free_msg(start_queue, start);
+ union sigval sival;
+ sival.sival_int = 0;
+ if(sigqueue(local_pid, STOP_SIGNAL, sival) < 0){ // if sending the signal failed
+ fprintf(stderr, "sigqueue STOP_SIGNAL (which is %d) with pid %d failed with errno %d: ", STOP_SIGNAL, local_pid, errno);
+ perror(NULL);
+ }
+}
+
+template<class T, class S> bool AsyncAction<T, S>::IsDone(int32_t count){
+ CheckStop();
+ async_action_status<S> *status = (async_action_status<S> *)aos_queue_read_msg(status_queue, PEEK | NON_BLOCK);
+ // below = there is one running && it's the right one && it's done
+ bool r = status != NULL && status->count == GetCount(count) && ((status->done_status & 0x02) != 0);
+ aos_queue_free_msg(status_queue, status);
+ return r;
+}
+template<class T, class S> uint16_t AsyncAction<T, S>::Join(int32_t count_in){
+ const uint16_t count = GetCount(count_in);
+ if(count == 0){
+ fprintf(stderr, "not joining non-existent run 0\n");
+ return 0;
+ }
+ async_action_status<S> *status = NULL;
+ done_index = 0; // the queue's message numbering might have been reset
+ do {
+ aos_queue_free_msg(status_queue, status);
+ CheckStop();
+ status = (async_action_status<S> *)aos_queue_read_msg_index(status_queue, FROM_END, &done_index);
+ } while(status != NULL && (status->done_status & 0x02) == 0 && (status->count == count));
+ if(status == NULL){
+ fprintf(stderr, "bad news at %s: %d\n", __FILE__, __LINE__);
+ return 0;
+ }
+ aos_queue_free_msg(status_queue, status);
+ return count;
+}
+template<class T, class S> bool AsyncAction<T, S>::GetNextStatus(S &status_out, int32_t count_in){
+ async_action_status<S> *status = NULL;
+start:
+ CheckStop();
+ const uint16_t count = GetCount(count_in);
+ if(count != next_status_count){ // reset the index if another one gets started in case the queue indexes get reset
+ next_status_count = count;
+ status_index = 0;
+ }
+ status = (async_action_status<S> *)aos_queue_read_msg_index(status_queue, FROM_END, &status_index);
+ if(status == NULL)
+ goto start;
+ if(status->count != count){
+ aos_queue_free_msg(status_queue, status);
+ return false;
+ }
+ bool r = (status->done_status & 0x01) != 0;
+ memcpy(&status_out, &status->status, sizeof(S));
+ aos_queue_free_msg(status_queue, status);
+ return r;
+}
+template<class T, class S> bool AsyncAction<T, S>::GetStatus(S &status_out, int32_t count){
+ CheckStop();
+ async_action_status<S> *status = (async_action_status<S> *)aos_queue_read_msg(status_queue, PEEK | NON_BLOCK);
+ if(status == NULL)
+ return false;
+ if(status->count != GetCount(count)){
+ aos_queue_free_msg(status_queue, status);
+ return false;
+ }
+ bool r = (status->done_status & 0x01) != 0;
+ memcpy(&status_out, &status->status, sizeof(S));
+ aos_queue_free_msg(status_queue, status);
+ return r;
+}
+
+template<class T, class S> void AsyncAction<T, S>::PostStatus(S &status_in){
+ CheckStop();
+ async_action_status<S> *status = (async_action_status<S> *)aos_queue_get_msg(status_queue);
+ if(status == NULL)
+ return;
+ memcpy(&local_status, &status_in, sizeof(S));
+ memcpy(&status->status, &status_in, sizeof(S));
+ status->done_status = 0x01;
+ local_done_status = 0x01;
+ status->pid = local_pid;
+ status->resource_entity = resource_entity;
+ if(aos_queue_write_msg(status_queue, status, OVERRIDE) < 0){
+ local_done_status = 0;
+ memset(&local_status, 0x00, sizeof(S));
+ aos_queue_free_msg(status_queue, status);
+ }
+}
+template<class T, class S> template<int (*O)(aos_resource_entity *, aos_resource *)> inline bool AsyncAction<T, S>::ResourceOp(uint16_t resource){
+ CheckStop();
+ if(resource_entity == NULL){
+ fprintf(stderr, "no started AsyncAction detected in this process\n");
+ return false;
+ }
+ switch(O(resource_entity, aos_resource_get(resource))){
+ case 0:
+ break;
+ case 1:
+ return false;
+ case -1:
+ throw resourceexception();
+ }
+ return true;
+}
+template<class T, class S> void AsyncAction<T, S>::RequestResource(uint16_t resource){
+ if(ResourceOp<aos_resource_request>(resource)){
+ resources[resource] = 1;
+ }else{
+ throw resourceexception(); // if we can't get a resource, we just want to stop
+ }
+}
+template<class T, class S> bool AsyncAction<T, S>::TryRequestResource(uint16_t resource){
+ if(ResourceOp<aos_resource_request>(resource)){
+ resources[resource] = 1;
+ return true;
+ }else{
+ return false;
+ }
+}
+template<class T, class S> void AsyncAction<T, S>::ReleaseResource(uint16_t resource){
+ if(ResourceOp<aos_resource_release>(resource)){
+ if(resources.erase(resource) != 1)
+ fprintf(stderr, "warning: value for resource %d wasn't 1\n", resource);
+ }
+}
+
+#if 0
+// from gcc's (used 4.6.2) libjava/include/i386-signal.h
+/* We use kernel_sigaction here because we're calling the kernel
+ directly rather than via glibc. The sigaction structure that the
+ syscall uses is a different shape from the one in userland and not
+ visible to us in a header file so we define it here. */
+extern "C"
+{
+ struct kernel_sigaction
+ {
+ void (*k_sa_sigaction)(int,siginfo_t *,void *);
+ unsigned long k_sa_flags;
+ void (*k_sa_restorer) (void);
+ sigset_t k_sa_mask;
+ };
+}
+#define RESTORE(name, syscall) RESTORE2 (name, syscall)
+#define RESTORE2(name, syscall) \
+asm \
+ ( \
+ ".text\n" \
+ ".byte 0 # Yes, this really is necessary\n" \
+ " .align 16\n" \
+ "__" #name ":\n" \
+ " movl $" #syscall ", %eax\n" \
+ " int $0x80" \
+ );
+/* The return code for realtime-signals. */
+RESTORE (restore_rt, __NR_rt_sigreturn)
+void restore_rt (void) asm ("__restore_rt")
+ __attribute__ ((visibility ("hidden")));
+#define INIT_SIGNAL(signal, sigaction) \
+do \
+ { \
+ struct kernel_sigaction act; \
+ act.k_sa_sigaction = sigaction; \
+ sigemptyset (&act.k_sa_mask); \
+ act.k_sa_flags = SA_SIGINFO|0x4000000; \
+ act.k_sa_restorer = restore_rt; \
+ syscall (SYS_rt_sigaction, signal, &act, NULL, _NSIG / 8); \
+ } \
+while (0)
+/* Unblock a signal. Unless we do this, the signal may only be sent
+ once. */
+static void
+unblock_signal (int signum __attribute__ ((__unused__)))
+{
+ sigset_t sigs;
+
+ sigemptyset (&sigs);
+ sigaddset (&sigs, signum);
+ sigprocmask (SIG_UNBLOCK, &sigs, NULL);
+}
+#endif
+
+template<class T, class S> void AsyncAction<T, S>::sig_action(int signum, siginfo_t *, void *){
+ // TODO really shouldn't be using stdio in here (check before changing)
+ /*unblock_signal(signum);
+ // MAKE_THROW_FRAME(exception)
+ std::exception *exception = new std::exception;
+ throw exception;*/
+ fprintf(stderr, "received signal %d\n", signum);
+ if(signum == STOP_SIGNAL)
+ interrupt |= 0x01;
+ else if(signum == RESOURCE_KILL_SIGNAL)
+ interrupt |= 0x02;
+ else if(signum == SIGINT || signum == SIGTERM)
+ interrupt |= 0x04;
+ else
+ fprintf(stderr, "unknown signal %d\n", signum);
+}
+template<class T, class S> int AsyncAction<T, S>::Run(uint8_t priority) {
+ interrupt = 0;
+ struct sigaction sigact;
+ sigact.sa_sigaction = sig_action;
+ sigact.sa_flags = 0;
+ sigaction(STOP_SIGNAL, &sigact, NULL);
+ sigaction(RESOURCE_KILL_SIGNAL, &sigact, NULL);
+ sigaction(SIGINT, &sigact, NULL);
+ sigaction(SIGTERM, &sigact, NULL); // kill from the command line default
+
+ if(resource_entity != NULL){
+ fprintf(stderr, "resource_entity isn't already null, which means that this is the second Run being called in this process or something (which isn't allowed...)\n");
+ return -1;
+ }
+ resource_entity = aos_resource_entity_create(priority);
+
+ async_action_status<S> *status = (async_action_status<S> *)aos_queue_get_msg(status_queue);
+ if(status == NULL)
+ return -1;
+ //memset(status + offsetof(aync_action_status<S>, status->status), 0x00, sizeof(S));
+ status->count = 1;
+ status->done_status = 0;
+ local_done_status = 0;
+ local_pid = getpid();
+ fprintf(stderr, "local_pid=%d STOP_SIGNAL is currently %d\n", local_pid, STOP_SIGNAL);
+ status->pid = local_pid;
+ status->resource_entity = resource_entity;
+ // put the initial status in
+ if(aos_queue_write_msg(status_queue, status, OVERRIDE) < 0){
+ aos_queue_free_msg(status_queue, status);
+ return -1;
+ }
+
+ // clear out any pending start messages
+ async_action_start<T> *start = (async_action_start<T> *)aos_queue_read_msg(start_queue, NON_BLOCK);
+ aos_queue_free_msg(start_queue, start);
+
+ OnStart();
+
+ T args;
+ uint16_t current_count;
+ while(true){
+ interrupt = 0;
+ // wait for a new start message
+ start = (async_action_start<T> *)aos_queue_read_msg(start_queue, PEEK);
+ if(start == NULL){
+ if(interrupt & 0x04)
+ break;
+ continue;
+ }
+ memcpy(&args, &start->args, sizeof(T));
+ current_count = start->count;
+ if(start->parent == NULL){ // Start isn't getting called from a process with an AsyncAction implementation running in it
+ start->parent = aos_resource_entity_root_get();
+ }
+ aos_resource_entity_set_parent(resource_entity, start->parent);
+ aos_queue_free_msg(start_queue, start);
+ status = (async_action_status<S> *)aos_queue_get_msg(status_queue);
+ if(status == NULL){
+ fprintf(stderr, "%s: %d: could not get a status message to write initial status to\n", __FILE__, __LINE__);
+ continue;
+ }
+ status->done_status = local_done_status = 0;
+ status->pid = local_pid;
+ status->count = current_count;
+ status->resource_entity = resource_entity;
+ if(aos_queue_write_msg(status_queue, status, OVERRIDE) < 0)
+ aos_queue_free_msg(status_queue, status);
+
+ try {
+ DoAction(args);
+ } catch (stopexception &e) {
+ fprintf(stderr, "caught stopexception\n");
+ } catch (resourceexception &e) {
+ fprintf(stderr, "caught resourceexception\n");
+ } catch (...) {
+ fprintf(stderr, "caught another exception... (bad news)\n");
+ }
+
+ start = (async_action_start<T> *)aos_queue_read_msg(start_queue, NON_BLOCK);
+ if(start == NULL){
+ fprintf(stderr, "somebody else consumed the start message (at %s: %d)\n", __FILE__, __LINE__);
+ } else {
+ aos_queue_free_msg(start_queue, start);
+ }
+
+ status = (async_action_status<S> *)aos_queue_get_msg(status_queue);
+ if(status == NULL){
+ fprintf(stderr, "couldn't get a message to write that we're finished in to %s: %d\n", __FILE__, __LINE__);
+ continue;
+ }
+ memcpy(&status->status, &local_status, sizeof(S));
+ status->done_status = local_done_status | 0x02;
+ status->pid = local_pid;
+ status->count = current_count;
+ status->resource_entity = resource_entity;
+ if(aos_queue_write_msg(status_queue, status, OVERRIDE) < 0)
+ aos_queue_free_msg(status_queue, status);
+
+ std::map<uint16_t, uint8_t>::iterator it;
+ for(it = resources.begin(); it != resources.end(); ++it){
+ ReleaseResource(it->first);
+ }
+ if(!resources.empty()){
+ fprintf(stderr, "resources isn't empty after releasing everything in it. clearing it\n");
+ resources.clear();
+ }
+
+ if(interrupt & 0x04)
+ break;
+ }
+ OnEnd();
+ return 0;
+}
+
+template<class T, class S> void AsyncAction<T, S>::Sleep(double seconds){
+ timespec ts;
+ clock_gettime(CLOCK_MONOTONIC, &ts);
+ ts.tv_sec += (time_t)floor(seconds);
+ ts.tv_nsec += (long)((seconds - floor(seconds)) * 1000000000);
+ if(ts.tv_nsec > 1000000000){
+ ts.tv_nsec -= 1000000000;
+ ts.tv_sec += 1;
+ }
+ int rv;
+ do {
+ CheckStop();
+ rv = clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &ts, NULL);
+ } while(rv);
+}
+
+template<class T, class S> void AsyncAction<T, S>::DoAction(__attribute__((unused)) T &args){
+ fprintf(stderr, "this (at %s: %d) should never get run\n", __FILE__, __LINE__);
+ *((int *)NULL) = 0;
+}
+
+} // namespace aos
+
diff --git a/aos/atom_code/async_action/AsyncAction.h b/aos/atom_code/async_action/AsyncAction.h
new file mode 100644
index 0000000..31be206
--- /dev/null
+++ b/aos/atom_code/async_action/AsyncAction.h
@@ -0,0 +1,155 @@
+#ifndef _AOS_ASYNC_ACTION_H_
+#define _AOS_ASYNC_ACTION_H_
+
+#include <stdint.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+#include <signal.h>
+
+#include <string>
+#include <map>
+#include <type_traits>
+
+#include "aos/aos_core.h"
+#include "aos/common/type_traits.h"
+
+class AsyncActionTest;
+
+namespace aos {
+ // S is status type T is parameter type
+
+ template<class S> struct async_action_status {
+ S status;
+ uint8_t done_status; // 1 = valid status, 2 = done
+ uint16_t count;
+ pid_t pid;
+ aos_resource_entity *resource_entity;
+ };
+ template<class T> struct async_action_start {
+ T args;
+ uint16_t count;
+ aos_resource_entity *parent;
+ };
+
+ class AsyncActionRunner;
+ class ResourceAction_t;
+
+ class AsyncActionStatics {
+ friend class ResourceAction_t; // a testing AsyncAction that has to mess with resource stuff
+ protected:
+ class stopexception : public std::exception {
+ virtual const char* what() const throw() {
+ return "This exception indicates that the AsyncAction was stopped. This message should never show up anywhere.";
+ }
+ public:
+ stopexception() : std::exception() {}
+ };
+ class resourceexception : public std::exception {
+ virtual const char* what() const throw() {
+ return "This exception indicates that the AsyncAction was stopped due to resource contention. This message should never show up anywhere.";
+ }
+ public:
+ resourceexception() : std::exception() {}
+ };
+
+ // 1 = stop current DoAction
+ // 2 = stop corrent DoAction because of resource issues
+ // 4 = SIGINT pending (nicely close everything down first)
+ static volatile uint8_t interrupt;
+ static const int STOP_SIGNAL;
+ static aos_resource_entity *resource_entity;
+
+ // throw any exceptions indicated by signals
+ static inline void CheckStop(){
+ if(interrupt & (0x01 | 0x04)) {
+ throw stopexception();
+ fprintf(stderr, "the code should never ever get here (%s: %d)\n", __FILE__, __LINE__);
+ }else if(interrupt & 0x02) {
+ throw resourceexception();
+ fprintf(stderr, "the code should never ever get here (%s: %d)\n", __FILE__, __LINE__);
+ }
+ }
+ };
+
+ // S and T have to be structs
+ // T is sTart and S is status
+ // public functions (except for constructor) should be called on this AsyncAction
+ // in processes other than the one Run ing this AsyncAction
+ // vice versa for protected ones
+ template<class T, class S> class AsyncAction : public AsyncActionStatics {
+ static_assert(shm_ok<async_action_start<T>>::value,
+ "T must go through shared memory");
+ static_assert(shm_ok<async_action_status<S>>::value,
+ "S must go through shared memory");
+ friend class AsyncActionRunner;
+ friend class ::AsyncActionTest;
+ public:
+ AsyncAction(const std::string name);
+
+ // returns what the count will be throughout this run
+ // return of 0 indicates error (didn't start)
+ uint16_t Start(T &args);
+
+ // -1 for count means use the static one
+ // aka !IsRunning()
+ bool IsDone(int32_t count = -1);
+ // returns which one it joined
+ uint16_t Join(int32_t count = -1);
+ // return is whether there is an actual status or just garbage
+ bool GetStatus(S &status_out, int32_t count = -1) __attribute__ ((warn_unused_result));
+ // waits for a new good status
+ bool GetNextStatus(S &status_out, int32_t count = -1) __attribute__ ((warn_unused_result));
+
+ void Stop(int32_t count = -1);
+ protected:
+ // starts infinite loop that waits for Starts
+ // returns 0 for success, negative for error
+ // gets called by generated code
+ int Run(uint8_t priority);
+
+ virtual void DoAction(T &args);
+ // should only be called from DoAction
+ void PostStatus(S &status_in);
+ void RequestResource(uint16_t resource);
+ // returns whether succeeded
+ bool TryRequestResource(uint16_t resource);
+ void ReleaseResource(uint16_t resource);
+
+ // called at the beginning and end of Run
+ virtual void OnStart() {}
+ virtual void OnEnd() {}
+
+ // this should be the only sleep (or variant thereof) that gets called
+ void Sleep(double seconds);
+ private:
+ aos_queue *status_queue, *start_queue;
+
+ uint16_t local_count;
+ S local_status;
+ uint8_t local_done_status;
+ pid_t local_pid;
+
+ template<int (*O)(aos_resource_entity *, aos_resource *)> bool ResourceOp(uint16_t resource);
+ std::map<uint16_t, uint8_t> resources;
+
+ // for read_msg_index
+ int done_index, status_index;
+ uint16_t next_status_count; // uses it to figure out when to reset status_index
+
+ // return the default if appropriate
+ inline uint16_t GetCount(int32_t in){
+ if(in < 0)
+ return local_count;
+ else
+ return (uint16_t)in;
+ }
+
+ static void sig_action(int, siginfo_t *, void *);
+ };
+
+} // namespace aos
+
+#include "AsyncAction.cpp.inc" // to make the template stuff work
+
+#endif
diff --git a/aos/atom_code/async_action/AsyncActionHandle.h b/aos/atom_code/async_action/AsyncActionHandle.h
new file mode 100644
index 0000000..8088848
--- /dev/null
+++ b/aos/atom_code/async_action/AsyncActionHandle.h
@@ -0,0 +1,17 @@
+#ifndef __AOS__ASYNC_ACTION_HANDLE_H_
+#define __AOS__ASYNC_ACTION_HANDLE_H_
+
+namespace aos {
+
+ class AsyncActionHandle {
+ public:
+ virtual bool IsDone() = 0;
+ virtual uint16_t Join() = 0;
+ virtual uint16_t Join(int32_t count) = 0;
+ virtual void Stop() = 0;
+ virtual void Stop(int32_t count) = 0;
+ };
+
+} // namespace aos
+
+#endif
diff --git a/aos/atom_code/async_action/AsyncActionRunner.h b/aos/atom_code/async_action/AsyncActionRunner.h
new file mode 100644
index 0000000..148d13a
--- /dev/null
+++ b/aos/atom_code/async_action/AsyncActionRunner.h
@@ -0,0 +1,15 @@
+#ifndef __AOS_ASYNC_ACTION_RUNNER_H_
+#define __AOS_ASYNC_ACTION_RUNNER_H_
+
+#include "aos/atom_code/async_action/AsyncAction.h"
+
+namespace aos {
+ class AsyncActionRunner {
+ public:
+ template<class T, class S> inline static int Run(AsyncAction<T, S> &action, uint8_t priority) {
+ return action.Run(priority);
+ }
+ };
+}
+
+#endif
diff --git a/aos/atom_code/async_action/AsyncAction_real.cpp b/aos/atom_code/async_action/AsyncAction_real.cpp
new file mode 100644
index 0000000..9a0be1d
--- /dev/null
+++ b/aos/atom_code/async_action/AsyncAction_real.cpp
@@ -0,0 +1,10 @@
+#include "AsyncAction.h"
+
+using namespace aos;
+
+volatile uint8_t AsyncActionStatics::interrupt = 0;
+
+const int AsyncActionStatics::STOP_SIGNAL = SIGRTMIN + 4;
+
+aos_resource_entity *AsyncActionStatics::resource_entity = NULL;
+
diff --git a/aos/atom_code/async_action/AsyncAction_test.cpp b/aos/atom_code/async_action/AsyncAction_test.cpp
new file mode 100644
index 0000000..bdd4002
--- /dev/null
+++ b/aos/atom_code/async_action/AsyncAction_test.cpp
@@ -0,0 +1,115 @@
+#include "TestAction.h"
+#include "ResourceAction.h"
+extern "C"{
+#include <resource_internal.h>
+}
+
+#include <gtest/gtest.h>
+
+#include "sharedmem_test_setup.h"
+
+using namespace aos;
+
+class AsyncActionTest : public ExecVeTestSetup{
+ protected:
+ virtual void SetUp(){
+ AddProcess("../bin/TestAction");
+ AddProcess("../bin/ResourceAction");
+ //AddProcess("/home/brians/bin/wait_5s.sh");
+ AddProcess("../bin/ResourceActionChild");
+
+ ExecVeTestSetup::SetUp();
+ }
+
+ template<class H, class S, class T> bool HasResource(const uint16_t resource, H &handle){
+ /*bool r = AOS_RESOURCE_STATE_GET_HAS_IT(resource, handle.GetInstance().resource_entity);
+ EXPECT_EQ(r, handle.GetInstance().resources.count(resource)) << "the AsyncAction doesn't know whether it has resource " << resource << " or not";
+ return r;*/
+
+ /*const AsyncAction<S, T> &action = handle.GetInstance();
+ async_action_start<S> *start = (async_action_start<S> *)aos_queue_read_message(action.start_queue, PEEK | NON_BLOCK);
+ ASSERT_NE(NULL, start);
+ bool r = AOS_RESOURCE_STATE_GET_HAS_IT(resource, start->parent);
+ aos_queue_free_msg(action.start_queue, start);
+ return r;*/
+
+ AsyncAction<S, T> &action = (AsyncAction<S, T> &)handle.GetInstance();
+ async_action_status<T> *status = (async_action_status<T> *)aos_queue_read_msg(action.status_queue, PEEK | NON_BLOCK);
+ EXPECT_TRUE(status != NULL) << "if this failed, we're going to segfault next";
+ bool r = AOS_RESOURCE_STATE_GET_HAS_IT(resource, status->resource_entity);
+ aos_queue_free_msg(action.status_queue, status);
+ return r;
+ }
+
+ // tests from the google doc (https://docs.google.com/document/d/1gzRrVcqL2X9VgNQUI5DrvLVVVziIH7c5ZerATVbiS7U/edit?hl=en_US) (referenced by the numbers in the drawing)
+ // up here so they can be called with multiple inputs and checked for correct outputs
+ // return = number of sub-action call it failed at (1 = top level one etc) (0 = succeeded)
+ int GoogleDocTest1(uint8_t in_state){
+ return ResourceAction.Execute(0x01, 0x01, 1, in_state).failed;
+ }
+
+ virtual void TearDown(){
+ TestAction.Free();
+ LeftDrive.Free();
+ ResourceAction.Free();
+ ResourceAction.Free();
+
+ ExecVeTestSetup::TearDown();
+ }
+};
+
+TEST_F(AsyncActionTest, StartStop){
+ TestAction.Start(5, 3);
+ TestAction.Stop();
+ PercolatePause();
+ EXPECT_TRUE(TestAction.IsDone());
+}
+TEST_F(AsyncActionTest, AlternateName){
+ EXPECT_FALSE(LeftDrive.IsDone());
+}
+
+TEST_F(AsyncActionTest, Join){
+ TestAction.Start(0.1, 3);
+ EXPECT_FALSE(TestAction.IsDone());
+ TestAction.Join();
+ EXPECT_TRUE(TestAction.IsDone());
+}
+TEST_F(AsyncActionTest, JoinAgain){
+ uint16_t instance = TestAction.Start(0.1, 3);
+ TestAction.Join();
+ EXPECT_TRUE(TestAction.IsDone());
+ timespec ts;
+ clock_gettime(CLOCK_MONOTONIC, &ts);
+ TestAction.Join(instance);
+ timespec ts2;
+ clock_gettime(CLOCK_MONOTONIC, &ts2);
+ long diff = ts2.tv_nsec - ts.tv_nsec;
+ diff += (ts2.tv_sec - ts.tv_sec) * 1000000000;
+ EXPECT_LT(diff, 50000);
+}
+TEST_F(AsyncActionTest, Execute){
+ TestAction.Execute(0.06, 3);
+ EXPECT_TRUE(TestAction.IsDone());
+}
+
+TEST_F(AsyncActionTest, Release){
+ TestAction.Start(0.1, -4);
+ while(!TestAction.IsDone()){
+ if(TestAction.GetNextStatus())
+ EXPECT_EQ(TestAction.GetLastStatus().loops > 2, !(HasResource<TestActionHandle, testing_status, testing_args>(test_resource1, TestAction)));
+ }
+}
+TEST_F(AsyncActionTest, ReleaseBad){
+ TestAction.Start(-0.01, 5);
+}
+TEST_F(AsyncActionTest, ImplicitRelease){
+ TestAction.Execute(0.02, 4);
+ EXPECT_FALSE((HasResource<TestActionHandle, testing_status, testing_args>(test_resource1, TestAction)));
+}
+
+//TODO test killing or not based on priority (and inherited priority...)
+
+TEST_F(AsyncActionTest, GoogleDoc111){
+ EXPECT_EQ(3, GoogleDocTest1(3));
+}
+
diff --git a/aos/atom_code/async_action/ResourceAction.act b/aos/atom_code/async_action/ResourceAction.act
new file mode 100644
index 0000000..46e22fb
--- /dev/null
+++ b/aos/atom_code/async_action/ResourceAction.act
@@ -0,0 +1,13 @@
+args resource_args {
+ // 1 = request, 2 = release, 4 = child run, 8 = child request, 16 = child release, all others 0
+ uint8_t first;
+ uint8_t second;
+
+ int number; // top level is 1
+
+ uint8_t state_to_set; // first 2 bits are this one, next 2 bits are for parent
+};
+status resource_status {
+ int failed; // 0 means none have failed yet
+};
+priority 100;
diff --git a/aos/atom_code/async_action/ResourceActionChild.act b/aos/atom_code/async_action/ResourceActionChild.act
new file mode 100644
index 0000000..5e8226a
--- /dev/null
+++ b/aos/atom_code/async_action/ResourceActionChild.act
@@ -0,0 +1,8 @@
+args resource_child_args{
+ // 1 = request, 2 = release
+ uint8_t actions;
+}
+status resource_child_status{
+ bool success;
+}
+priority 70;
diff --git a/aos/atom_code/async_action/ResourceActionChild_t.cpp b/aos/atom_code/async_action/ResourceActionChild_t.cpp
new file mode 100644
index 0000000..c1a2601
--- /dev/null
+++ b/aos/atom_code/async_action/ResourceActionChild_t.cpp
@@ -0,0 +1,13 @@
+#include "ResourceActionChild.h"
+
+void ResourceActionChild_t::DoAction(uint8_t actions){
+ if(actions & 0x01)
+ if(TryRequestResource(test_resource1)){
+ PostStatus(false);
+ return;
+ }
+ if(actions & 0x02)
+ ReleaseResource(test_resource1);
+ PostStatus(true);
+}
+
diff --git a/aos/atom_code/async_action/ResourceAction_t.cpp b/aos/atom_code/async_action/ResourceAction_t.cpp
new file mode 100644
index 0000000..99d9c7e
--- /dev/null
+++ b/aos/atom_code/async_action/ResourceAction_t.cpp
@@ -0,0 +1,40 @@
+#define AOS_ResourceAction_t_HEADER_FRAG int DoSub(uint8_t slot, int in_number);
+
+#include "ResourceAction.h"
+#include "ResourceActionChild.h"
+extern "C"{
+#include <resource_internal.h>
+}
+
+int ResourceAction_t::DoSub(uint8_t slot, int in_number){
+ if(slot & 0x01)
+ if(TryRequestResource(test_resource1)){
+ PostStatus(in_number + 1);
+ return 0;
+ }
+ if(slot & 0x02)
+ ReleaseResource(test_resource1);
+ if(slot & 0x04){
+ if(!ResourceActionChild.Execute(slot << 3).success){
+ PostStatus(in_number + 2);
+ return 0;
+ }
+ }
+ return in_number + ((slot & (0x01 | 0x02)) ? 1 : 0) + ((slot & 0x04) ? 1 : 0);
+}
+void ResourceAction_t::DoAction(uint8_t first, uint8_t second, int number, uint8_t state_to_set){
+ printf("start of ResourceAction.DoAction\n");
+ AOS_RESOURCE_STATE_SET_ON((AOS_RESOURCE_STATE_WANTS_IT | AOS_RESOURCE_STATE_HAS_PASSED_DOWN) & state_to_set, test_resource1, ::AsyncActionStatics::resource_entity);
+ AOS_RESOURCE_STATE_SET_OFF((AOS_RESOURCE_STATE_WANTS_IT | AOS_RESOURCE_STATE_HAS_PASSED_DOWN) & state_to_set, test_resource1, ::AsyncActionStatics::resource_entity);
+ AOS_RESOURCE_STATE_SET_ON((AOS_RESOURCE_STATE_WANTS_IT | AOS_RESOURCE_STATE_HAS_PASSED_DOWN) & (state_to_set >> 2), test_resource1, aos_resource_entity_root_get());
+ AOS_RESOURCE_STATE_SET_OFF((AOS_RESOURCE_STATE_WANTS_IT | AOS_RESOURCE_STATE_HAS_PASSED_DOWN) & state_to_set >> 2, test_resource1, aos_resource_entity_root_get());
+ printf("set state\n");
+
+ number = DoSub(first, number);
+ printf("did first\n");
+ if(number == 0) // error
+ return;
+ number = DoSub(second, number);
+ printf("did second\n");
+}
+
diff --git a/aos/atom_code/async_action/TestAction.act b/aos/atom_code/async_action/TestAction.act
new file mode 100644
index 0000000..96c940b
--- /dev/null
+++ b/aos/atom_code/async_action/TestAction.act
@@ -0,0 +1,13 @@
+args testing_args {
+ double seconds;
+ int loops;
+};
+status testing_status {
+ int loops;
+ double total_seconds;
+};
+async_queue LeftDrive;
+async_queue TestAction;
+//has OnEnd;
+//has OnStart;
+priority 50;
diff --git a/aos/atom_code/async_action/TestAction_t.cpp b/aos/atom_code/async_action/TestAction_t.cpp
new file mode 100644
index 0000000..1e99529
--- /dev/null
+++ b/aos/atom_code/async_action/TestAction_t.cpp
@@ -0,0 +1,35 @@
+#include "TestAction.h"
+#include <AsyncActionRunner.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <unistd.h>
+
+//void TestingAction_t::OnStart() {printf("started\n");}
+//void TestingAction_t::OnEnd() {printf("ended\n");}
+void TestAction_t::DoAction(double seconds, int loops) {
+ printf("start of DoAction\n");
+ RequestResource(test_resource1);
+ bool release = loops < 0;
+ if(release)
+ loops *= -1;
+ bool release_bad = seconds < 0;
+ if(release_bad)
+ seconds *= -1;
+ int i;
+ for(i = 0; i < loops; ++i) {
+ Sleep(seconds);
+ printf("posting for loop %d\n", i);
+ PostStatus(i, seconds * i);
+ printf("posted for loop %d\n", i);
+ if(release && i > loops / 2){
+ printf("releasing resource\n");
+ ReleaseResource(test_resource1);
+ }
+ if(release_bad && i > loops / 2){
+ printf("releasing resource which has not been requested\n");
+ ReleaseResource(test_resource2);
+ }
+ }
+ printf("end of DoAction\n");
+}
+
diff --git a/aos/atom_code/async_action/async_action.gyp b/aos/atom_code/async_action/async_action.gyp
new file mode 100644
index 0000000..5f5bf55
--- /dev/null
+++ b/aos/atom_code/async_action/async_action.gyp
@@ -0,0 +1,13 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'AsyncAction_test',
+ 'type': 'executable',
+ 'sources': [
+ 'AsyncACtion_test.cpp',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ ],
+ ],
+},
diff --git a/aos/atom_code/camera/Buffers.cpp b/aos/atom_code/camera/Buffers.cpp
new file mode 100644
index 0000000..22b7337
--- /dev/null
+++ b/aos/atom_code/camera/Buffers.cpp
@@ -0,0 +1,160 @@
+#include "Buffers.h"
+#include "V4L2.h"
+
+#include <sys/mman.h>
+
+namespace aos {
+namespace camera {
+
+// Represents an actual v4l2 buffer.
+struct Buffers::Buffer {
+ void *start;
+ size_t length; // for munmap
+};
+const std::string Buffers::kFDServerName("/tmp/aos_fd_server");
+const std::string Buffers::kQueueName("CameraBufferQueue");
+const aos_type_sig Buffers::kSignature{sizeof(Message), 971, 1};
+
+int Buffers::CreateSocket(int (*bind_connect)(int, const sockaddr *, socklen_t)) {
+ union af_unix_sockaddr {
+ sockaddr_un un;
+ sockaddr addr;
+ } addr;
+ const int r = socket(AF_UNIX, SOCK_STREAM, 0);
+ if (r == -1) {
+ LOG(ERROR, "socket(AF_UNIX, SOCK_STREAM, 0) failed with %d: %s\n",
+ errno, strerror(errno));
+ return -1;
+ }
+ addr.un.sun_family = AF_UNIX;
+ memset(addr.un.sun_path, 0, sizeof(addr.un.sun_path));
+ strcpy(addr.un.sun_path, kFDServerName.c_str());
+ if (bind_connect(r, &addr.addr, sizeof(addr.un)) == -1) {
+ LOG(ERROR, "bind_connect(=%p)(%d, %p, %zd) failed with %d: %s\n",
+ bind_connect, r, &addr.addr, sizeof(addr.un), errno, strerror(errno));
+ close(r); // what are we going to do about an error?
+ return -1;
+ }
+ return r;
+}
+
+void Buffers::MMap() {
+ buffers_ = new Buffer[kNumBuffers];
+ v4l2_buffer buf;
+ for (unsigned int n = 0; n < kNumBuffers; ++n) {
+ memset(&buf, 0, sizeof(buf));
+ buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+ buf.memory = V4L2_MEMORY_MMAP;
+ buf.index = n;
+ if (xioctl(fd_, VIDIOC_QUERYBUF, &buf) == -1) {
+ LOG(FATAL, "ioctl VIDIOC_QUERYBUF(%d, %p) failed with %d: %s\n",
+ fd_, &buf, errno, strerror(errno));
+ }
+ buffers_[n].length = buf.length;
+ buffers_[n].start = mmap(NULL, buf.length,
+ PROT_READ | PROT_WRITE, MAP_SHARED,
+ fd_, buf.m.offset);
+ if (buffers_[n].start == MAP_FAILED) {
+ LOG(FATAL, "mmap(NULL, %zd, PROT_READ | PROT_WRITE, MAP_SHARED, %d, %jd)"
+ " failed with %d: %s\n", buf.length, fd_, static_cast<intmax_t>(buf.m.offset),
+ errno, strerror(errno));
+ }
+ }
+}
+
+void Buffers::Release() {
+ if (message_ != NULL) {
+ aos_queue_free_msg(queue_, message_);
+ message_ = NULL;
+ }
+}
+const void *Buffers::GetNext(bool block,
+ uint32_t *bytesused, timeval *timestamp, uint32_t *sequence) {
+ Release();
+
+ // TODO(brians) make sure the camera reader process hasn't died
+ do {
+ if (block) {
+ message_ = static_cast<const Message *>(aos_queue_read_msg(queue_, PEEK | BLOCK));
+ } else {
+ static int index = 0;
+ message_ = static_cast<const Message *>(aos_queue_read_msg_index(queue_, BLOCK,
+ &index));
+ }
+ } while (block && message_ == NULL);
+ if (message_ != NULL) {
+ if (bytesused != NULL) memcpy(bytesused, &message_->bytesused, sizeof(*bytesused));
+ if (timestamp != NULL) memcpy(timestamp, &message_->timestamp, sizeof(*timestamp));
+ if (sequence != NULL) memcpy(sequence, &message_->sequence, sizeof(*sequence));
+ return buffers_[message_->index].start;
+ } else {
+ return NULL;
+ }
+}
+
+int Buffers::FetchFD() {
+ int myfds[Buffers::kNumFDs]; // where to retrieve the fds into
+ char buf[CMSG_SPACE(sizeof(myfds))]; // ancillary data buffer
+
+ iovec data;
+ memset(&data, 0, sizeof(data));
+ char dummy;
+ data.iov_base = &dummy;
+ data.iov_len = sizeof(dummy);
+ msghdr msg;
+ memset(&msg, 0, sizeof(msg));
+ msg.msg_iov = &data;
+ msg.msg_iovlen = 1;
+ msg.msg_control = buf;
+ msg.msg_controllen = sizeof(buf);
+
+ switch (recvmsg(server_, &msg, 0)) {
+ case 0: // "the peer has performed an orderly shutdown"
+ LOG(FATAL, "the fd server shut down (connected on %d)\n", server_);
+ case -1:
+ LOG(FATAL, "recvmsg(server_(=%d), %p, 0) failed with %d: %s\n",
+ server_, &msg, errno, strerror(errno));
+ }
+ const cmsghdr *const cmsg = CMSG_FIRSTHDR(&msg);
+ if (cmsg == NULL) {
+ LOG(FATAL, "no headers in message\n");
+ }
+ if (cmsg->cmsg_len != CMSG_LEN(sizeof(myfds))) {
+ LOG(FATAL, "got wrong size. got %d but expected %zd\n",
+ cmsg->cmsg_len, CMSG_LEN(sizeof(myfds)));
+ }
+ if (cmsg->cmsg_level != SOL_SOCKET) {
+ LOG(FATAL, "cmsg_level=%d. expected SOL_SOCKET(=%d)\n", cmsg->cmsg_level, SOL_SOCKET);
+ }
+ if (cmsg->cmsg_type != SCM_RIGHTS) {
+ LOG(FATAL, "cmsg_type=%d. expected SCM_RIGHTS(=%d)\n", cmsg->cmsg_type, SCM_RIGHTS);
+ }
+ memcpy(myfds, CMSG_DATA(cmsg), sizeof(myfds));
+
+ return myfds[0];
+}
+Buffers::Buffers() : server_(CreateSocket(connect)), fd_(FetchFD()), message_(NULL) {
+ MMap();
+ queue_ = aos_fetch_queue(kQueueName.c_str(), &kSignature);
+}
+
+Buffers::~Buffers() {
+ Release();
+
+ for (unsigned i = 0; i < kNumBuffers; ++i) {
+ if (munmap(buffers_[i].start, buffers_[i].length) == -1) {
+ LOG(WARNING, "munmap(%p, %zd) for destruction failed with %d: %s\n",
+ buffers_[i].start, buffers_[i].length, errno, strerror(errno));
+ }
+ }
+ delete[] buffers_;
+
+ if (close(fd_) == -1) {
+ LOG(WARNING, "close(%d) for destruction failed with %d: %s\n",
+ fd_, errno, strerror(errno));
+ }
+}
+
+} // namespace camera
+} // namespace aos
+
diff --git a/aos/atom_code/camera/Buffers.h b/aos/atom_code/camera/Buffers.h
new file mode 100644
index 0000000..7f1206d
--- /dev/null
+++ b/aos/atom_code/camera/Buffers.h
@@ -0,0 +1,93 @@
+#ifndef AOS_ATOM_CODE_CAMERA_CAMERA_BUFFERS_H_
+#define AOS_ATOM_CODE_CAMERA_CAMERA_BUFFERS_H_
+
+#include <sys/socket.h>
+#include <sys/un.h>
+
+#include <string>
+
+#include "aos/aos_core.h"
+#include "aos/common/type_traits.h"
+
+namespace aos {
+namespace camera {
+
+class Reader;
+class Buffers {
+ // It has to do a lot of the same things as all the other ones, but it gets
+ // the information from different places (some of it gets sent out by it).
+ friend class Reader;
+ // Not an abstract name so that an existing one can just be unlinked without
+ // disturbing it if necessary (like with shm_link).
+ static const std::string kFDServerName;
+ // How many v4l2 buffers and other things that depend on that.
+ static const unsigned int kNumBuffers = 10;
+ // How many fds to transfer from the fd server.
+ // Used to make it clear which 1s are 1 and which are this.
+ static const size_t kNumFDs = 1;
+ // Creates a socket and calls either bind or connect.
+ // Returns a bound/connected socket or -1 (the reason for which will already
+ // have been logged at ERROR).
+ static int CreateSocket(int (*bind_connect)(int, const sockaddr *, socklen_t));
+
+ // File descriptor connected to the fd server. Used for detecting if the
+ // camera reading process has died.
+ // A value of -2 means don't check.
+ const int server_;
+ // Gets the fd (using server_).
+ int FetchFD();
+ // File descriptor for the v4l2 device (that's valid in this process of
+ // course).
+ const int fd_;
+
+ struct Buffer;
+ // Buffer[kNumBuffers]
+ Buffer *buffers_;
+ struct Message {
+ uint32_t index;
+ uint32_t bytesused;
+ timeval timestamp;
+ uint32_t sequence;
+ };
+ static_assert(shm_ok<Message>::value, "it's going through queues");
+ // The current one. Sometimes NULL.
+ const Message *message_;
+ static const std::string kQueueName;
+ static const aos_type_sig kSignature;
+ // NULL for the Reader one.
+ aos_queue *queue_;
+ // Make the actual mmap calls.
+ // Called by Buffers() automatically.
+ void MMap();
+ public:
+ Buffers();
+ // Will clean everything up.
+ // So that HTTPStreamer can create/destroy one for each client to make it
+ // simpler.
+ ~Buffers();
+
+ // Retrieves the next image. Will return the current one if it hasn't yet.
+ // Calls Release() at the beginning.
+ // NOTE: this means that the caller can't keep using references to the old
+ // return value after calling this function again
+ // block is whether to return NULL or wait for a new one
+ // the last 3 output parameters will be filled in straight from the
+ // v4l2_buffer if they're not NULL
+ // (see <http://v4l2spec.bytesex.org/spec/x5953.htm#V4L2-BUFFER> for details)
+ // NOTE: guaranteed to return a valid pointer if block is true
+ const void *GetNext(bool block,
+ uint32_t *bytesused, timeval *timestamp, uint32_t *sequence);
+ // Releases the most recent frame buffer. Automatically called by GetNext and
+ // the destructor. Safe to call multiple times without getting frames in
+ // between.
+ void Release();
+
+ // How big images are.
+ static const int32_t kWidth = 640, kHeight = 480;
+};
+
+} // namespace camera
+} // namespace aos
+
+#endif
+
diff --git a/aos/atom_code/camera/HTTPStreamer.cpp b/aos/atom_code/camera/HTTPStreamer.cpp
new file mode 100644
index 0000000..ad339a8
--- /dev/null
+++ b/aos/atom_code/camera/HTTPStreamer.cpp
@@ -0,0 +1,388 @@
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <fcntl.h>
+#include <unistd.h>
+#include <errno.h>
+#include <malloc.h>
+#include <sys/stat.h>
+#include <sys/types.h>
+#include <sys/time.h>
+#include <sys/mman.h>
+#include <netinet/ip.h>
+#include <sys/socket.h>
+#include <inttypes.h>
+
+#include <vector>
+
+#include "aos/common/Configuration.h"
+#include "aos/aos_core.h"
+#include "aos/atom_code/camera/Buffers.h"
+
+namespace aos {
+namespace camera {
+
+namespace {
+
+// doesn't like being a static class member
+static const unsigned char dht_table[] = {
+ 0xff, 0xc4, 0x01, 0xa2, 0x00, 0x00, 0x01, 0x05, 0x01, 0x01, 0x01, 0x01,
+ 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02,
+ 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, 0x01, 0x00, 0x03,
+ 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09,
+ 0x0a, 0x0b, 0x10, 0x00, 0x02, 0x01, 0x03, 0x03, 0x02, 0x04, 0x03, 0x05,
+ 0x05, 0x04, 0x04, 0x00, 0x00, 0x01, 0x7d, 0x01, 0x02, 0x03, 0x00, 0x04,
+ 0x11, 0x05, 0x12, 0x21, 0x31, 0x41, 0x06, 0x13, 0x51, 0x61, 0x07, 0x22,
+ 0x71, 0x14, 0x32, 0x81, 0x91, 0xa1, 0x08, 0x23, 0x42, 0xb1, 0xc1, 0x15,
+ 0x52, 0xd1, 0xf0, 0x24, 0x33, 0x62, 0x72, 0x82, 0x09, 0x0a, 0x16, 0x17,
+ 0x18, 0x19, 0x1a, 0x25, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x34, 0x35, 0x36,
+ 0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a,
+ 0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, 0x66,
+ 0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a,
+ 0x83, 0x84, 0x85, 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, 0x93, 0x94, 0x95,
+ 0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7, 0xa8,
+ 0xa9, 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba, 0xc2,
+ 0xc3, 0xc4, 0xc5, 0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4, 0xd5,
+ 0xd6, 0xd7, 0xd8, 0xd9, 0xda, 0xe1, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7,
+ 0xe8, 0xe9, 0xea, 0xf1, 0xf2, 0xf3, 0xf4, 0xf5, 0xf6, 0xf7, 0xf8, 0xf9,
+ 0xfa, 0x11, 0x00, 0x02, 0x01, 0x02, 0x04, 0x04, 0x03, 0x04, 0x07, 0x05,
+ 0x04, 0x04, 0x00, 0x01, 0x02, 0x77, 0x00, 0x01, 0x02, 0x03, 0x11, 0x04,
+ 0x05, 0x21, 0x31, 0x06, 0x12, 0x41, 0x51, 0x07, 0x61, 0x71, 0x13, 0x22,
+ 0x32, 0x81, 0x08, 0x14, 0x42, 0x91, 0xa1, 0xb1, 0xc1, 0x09, 0x23, 0x33,
+ 0x52, 0xf0, 0x15, 0x62, 0x72, 0xd1, 0x0a, 0x16, 0x24, 0x34, 0xe1, 0x25,
+ 0xf1, 0x17, 0x18, 0x19, 0x1a, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x35, 0x36,
+ 0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a,
+ 0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, 0x66,
+ 0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a,
+ 0x82, 0x83, 0x84, 0x85, 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, 0x93, 0x94,
+ 0x95, 0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7,
+ 0xa8, 0xa9, 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba,
+ 0xc2, 0xc3, 0xc4, 0xc5, 0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4,
+ 0xd5, 0xd6, 0xd7, 0xd8, 0xd9, 0xda, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7,
+ 0xe8, 0xe9, 0xea, 0xf2, 0xf3, 0xf4, 0xf5, 0xf6, 0xf7, 0xf8, 0xf9, 0xfa
+};
+
+const char kFirstHeader[] = "HTTP/1.0 200 OK\r\n"
+"Connection: close\r\n"
+"Server: AOS/0.0 Camera\r\n"
+"Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, "
+"post-check=0, max-age=0\r\n" // this and above from mjpg-streamer
+"Pragma: no-cache\r\n"
+"Expires: Mon, 3 Jan 2000 12:34:56 GMT\r\n" // also from mjpg-streamer
+"Content-Type: multipart/x-mixed-replace; boundary=boundarydonotcross\r\n";
+
+} // namespace
+
+class HTTPStreamer {
+ // Represents a single client. Handles all reading and writing of sockets and
+ // queues.
+ class Client {
+ enum class State {
+ kReadHeaders,
+ kWriteHeaders,
+ kWriteBoundary, // these last 2 loop to each other
+ kWriteImage,
+ kWriteDHT, // happens in the middle of kWriteImage
+ };
+ const int sock_;
+ State state_;
+ inline fd_set *GetFDSetForCurrentState(fd_set *read_fds,
+ fd_set *write_fds) {
+ if (state_ == State::kReadHeaders) {
+ return read_fds;
+ } else {
+ return write_fds;
+ }
+ }
+ // MUST BE LONG ENOUGH TO HOLD kBoundaryText WITH A BIGGISH # IN IT
+ char scratch_[4096];
+ int to_write_;
+ int zero_reads_;
+ static const int kMaxZeroReads = 2000;
+ size_t pos_, dht_pos_, dht_start_;
+ Buffers buffers_;
+ const void *current_;
+ uint32_t size_;
+
+ Client(const Client &);
+ void operator=(const Client &);
+
+ public:
+ explicit Client(int sock) : sock_(sock), state_(State::kReadHeaders),
+ zero_reads_(0), pos_(0) {}
+ ~Client() {
+ LOG(DEBUG, "closing socket %d\n", sock_);
+ if (close(sock_) == -1) {
+ LOG(INFO, "closing socket %d for destruction failed with %d: %s\n",
+ sock_, errno, strerror(errno));
+ }
+ }
+ // Set any fds necessary into the 2 arguments.
+ void FDSet(fd_set *read_fds, fd_set *write_fds) {
+ FD_SET(sock_, GetFDSetForCurrentState(read_fds, write_fds));
+ }
+ // The arguments are the same as the last FDSet call (after a successful
+ // select).
+ // Return value is whether or not to keep this one around.
+ bool Process(fd_set *read_fds, fd_set *write_fds) {
+ // if the socket we're waiting on isn't ready
+ if (!FD_ISSET(sock_, GetFDSetForCurrentState(read_fds, write_fds))) {
+ return true;
+ }
+
+ ssize_t ret;
+ switch (state_) {
+ case State::kReadHeaders:
+ if (pos_ >= sizeof(scratch_)) {
+ LOG(WARNING, "read too many bytes of headers on sock %d."
+ " somebody should increase the size of scratch_\n", sock_);
+ return false;
+ }
+ if (zero_reads_ > kMaxZeroReads) {
+ LOG(WARNING, "read 0 bytes %d times on sock %d. giving up\n",
+ zero_reads_, sock_);
+ return false;
+ }
+ ret = read(sock_, scratch_ + pos_, sizeof(scratch_) - pos_);
+ if (ret == -1) {
+ LOG(WARNING, "read(%d, %p, %zd) failed with %d: %s\n",
+ sock_, scratch_ + pos_, sizeof(scratch_) - pos_,
+ errno, strerror(errno));
+ return false;
+ }
+ pos_ += ret;
+ // if we just received \r\n\r\n (the end of the headers)
+ if (scratch_[pos_ - 4] == '\r' && scratch_[pos_ - 3] == '\n' &&
+ scratch_[pos_ - 2] == '\r' && scratch_[pos_ - 1] == '\n') {
+ LOG(INFO, "entering state kWriteHeaders"
+ " after %zd bytes of headers read\n", pos_ - 1);
+ pos_ = 0;
+ state_ = State::kWriteHeaders;
+ }
+ scratch_[pos_] = '\0';
+ if (ret == 0) {
+ ++zero_reads_;
+ } else {
+ zero_reads_ = 0;
+ LOG(DEBUG, "read %zd bytes of headers scratch_=%s\n",
+ ret, scratch_);
+ }
+ break;
+ case State::kWriteHeaders:
+ // this intentionally doesn't write the terminating \0 on the string
+ ret = write(sock_, kFirstHeader + pos_, sizeof(kFirstHeader) - pos_);
+ if (ret == -1) {
+ LOG(WARNING, "write(%d, %p, %zd) failed with %d: %s\n",
+ sock_, kFirstHeader + pos_, sizeof(kFirstHeader) - pos_,
+ errno, strerror(errno));
+ } else {
+ pos_ += ret;
+ if (pos_ >= sizeof(kFirstHeader)) {
+ current_ = NULL;
+ state_ = State::kWriteBoundary;
+ }
+ }
+ break;
+ case State::kWriteBoundary:
+ if (current_ == NULL) {
+ timeval timestamp;
+ current_ = buffers_.GetNext(false, &size_, ×tamp, NULL);
+
+ /*static int skip = 0;
+ if (current_ != NULL) skip = (skip + 1) % 30;
+ if (!skip) current_ = NULL;
+ if (current_ == NULL) break;*/
+
+#if 0
+ // set pos_ to where the first header starts
+ for (pos_ = 0; static_cast<const uint8_t *>(current_)[pos_] != 0xFF;
+ ++pos_);
+#else
+ pos_ = 0;
+#endif
+#if 0
+ // go through the frame looking for the start of frame marker
+ for (dht_start_ = 0;
+ static_cast<const uint8_t *>(current_)[dht_start_ + 0] !=
+ 0xFF &&
+ static_cast<const uint8_t *>(current_)[dht_start_ + 1] !=
+ 0xC0 &&
+ dht_start_ < size_; ++dht_start_)
+ printf("[%zd]=%"PRIx8" ", dht_start_,
+ static_cast<const uint8_t *>(current_)[dht_start_]);
+ if (dht_start_ >= size_) {
+ LOG(WARNING, "couldn't find start of frame marker\n");
+ return false;
+ }
+#else
+ dht_start_ = 0;
+#endif
+ dht_pos_ = 0;
+
+ // aos.ChannelImageGetter depends on the exact format of this
+ to_write_ = snprintf(scratch_, sizeof(scratch_),
+ "\r\n--boundarydonotcross\r\n"
+ "Content-Type: image/jpeg\r\n"
+ "Content-Length: %"PRId32"\r\n"
+ "X-Timestamp: %ld.%06ld\r\n"
+ "\r\n",
+ size_,
+ timestamp.tv_sec, timestamp.tv_usec);
+ }
+ ret = write(sock_, scratch_ + pos_, to_write_ - pos_);
+ if (ret == -1) {
+ LOG(WARNING, "write(%d, %p, %zd) failed with %d: %s\n",
+ sock_, scratch_ + pos_, to_write_ - pos_,
+ errno, strerror(errno));
+ return false;
+ } else {
+ pos_ += ret;
+ if (static_cast<ssize_t>(pos_) >= to_write_) {
+ pos_ = 0;
+ state_ = State::kWriteImage;
+ }
+ }
+ break;
+ case State::kWriteImage:
+ ret = write(sock_, static_cast<const char *>(current_) + pos_,
+ ((dht_start_ == 0) ? size_ : dht_start_) - pos_);
+ if (ret == -1) {
+ LOG(WARNING, "write(%d, %p, %zd) failed with %d: %s\n",
+ sock_, static_cast<const char *>(current_) + pos_,
+ ((dht_start_ == 0) ? size_ : dht_start_) - pos_,
+ errno, strerror(errno));
+ return false;
+ } else {
+ pos_ += ret;
+ if (dht_start_ == 0) {
+ if (pos_ >= size_) {
+ buffers_.Release();
+ current_ = NULL;
+ state_ = State::kWriteBoundary;
+ }
+ } else {
+ if (pos_ >= dht_start_) {
+ dht_start_ = 0;
+ state_ = State::kWriteDHT;
+ }
+ }
+ }
+ break;
+ case State::kWriteDHT:
+ ret = write(sock_, dht_table + dht_pos_,
+ sizeof(dht_table) - dht_pos_);
+ if (ret == -1) {
+ LOG(WARNING, "write(%d, %p, %zd) failed with %d: %s\n",
+ sock_, dht_table + dht_pos_, sizeof(dht_table) - dht_pos_,
+ errno, strerror(errno));
+ return false;
+ } else {
+ dht_pos_ += ret;
+ if (dht_pos_ >= sizeof(dht_table)) {
+ state_ = State::kWriteImage;
+ }
+ }
+ break;
+ default:
+ LOG(FATAL, "something weird happened\n");
+ }
+ return true;
+ }
+ };
+
+ const int bind_socket_;
+
+ public:
+ HTTPStreamer() : bind_socket_(socket(AF_INET, SOCK_STREAM, 0)) {
+ if (bind_socket_ < 0) {
+ LOG(FATAL, "socket(AF_INET, SOCK_STREAM, 0) failed with %d: %s\n",
+ errno, strerror(errno));
+ }
+
+ union {
+ sockaddr_in in;
+ sockaddr addr;
+ } bind_sockaddr;
+ memset(&bind_sockaddr, 0, sizeof(bind_sockaddr));
+ bind_sockaddr.in.sin_family = AF_INET;
+ bind_sockaddr.in.sin_port =
+ htons(static_cast<uint16_t>(aos::NetworkPort::kCameraStreamer));
+ bind_sockaddr.in.sin_addr.s_addr = htonl(INADDR_ANY);
+ int optval = 1;
+ setsockopt(bind_socket_, SOL_SOCKET, SO_REUSEADDR, &optval, sizeof(optval));
+ if (bind(bind_socket_, &bind_sockaddr.addr,
+ sizeof(bind_sockaddr.addr)) == -1) {
+ LOG(FATAL, "bind(%d, %p) failed because of %d: %s\n",
+ bind_socket_, &bind_sockaddr.addr, errno, strerror(errno));
+ }
+
+ if (listen(bind_socket_, 10) == -1) {
+ LOG(FATAL, "listen(%d, 10) failed because of %d: %s\n", bind_socket_,
+ errno, strerror(errno));
+ }
+ const int flags = fcntl(bind_socket_, F_GETFL, 0);
+ if (flags == -1) {
+ LOG(FATAL, "fcntl(%d, F_GETFL, 0) failed because of %d: %s\n",
+ bind_socket_, errno, strerror(errno));
+ }
+ if (fcntl(bind_socket_, F_SETFL, flags | O_NONBLOCK) == -1) {
+ LOG(FATAL, "fcntl(%d, F_SETFL, %x) failed because of %d: %s\n",
+ bind_socket_, flags | O_NONBLOCK, errno, strerror(errno));
+ }
+ }
+ void Run() {
+ signal(SIGPIPE, SIG_IGN);
+
+ std::vector<Client *> clients;
+ fd_set read_fds, write_fds;
+ while (true) {
+ FD_ZERO(&read_fds);
+ FD_ZERO(&write_fds);
+ FD_SET(bind_socket_, &read_fds);
+ for (auto it = clients.begin(); it != clients.end(); ++it) {
+ (*it)->FDSet(&read_fds, &write_fds);
+ }
+ switch (select(FD_SETSIZE, &read_fds, &write_fds,
+ NULL, // err
+ NULL)) { // timeout
+ case -1:
+ LOG(ERROR, "select(FD_SETSIZE(=%d), %p, %p, NULL, NULL) failed"
+ " because of %d: %s\n", FD_SETSIZE, &read_fds, &write_fds,
+ errno, strerror(errno));
+ continue;
+ case 0:
+ LOG(ERROR, "select with NULL timeout timed out...\n");
+ continue;
+ }
+
+ if (FD_ISSET(bind_socket_, &read_fds)) {
+ const int sock = accept4(bind_socket_, NULL, NULL, SOCK_NONBLOCK);
+ if (sock == -1) {
+ LOG(ERROR, "accept4(%d, NULL, NULL, SOCK_NONBLOCK(=%d) failed"
+ " because of %d: %s\n",
+ bind_socket_, SOCK_NONBLOCK, errno, strerror(errno));
+ } else {
+ clients.push_back(new Client(sock));
+ }
+ }
+
+ std::vector<std::vector<Client *>::iterator> to_remove;
+ for (auto it = clients.begin(); it != clients.end(); ++it) {
+ if (!(*it)->Process(&read_fds, &write_fds)) {
+ to_remove.push_back(it);
+ delete *it;
+ }
+ }
+ for (auto it = to_remove.rbegin(); it != to_remove.rend(); ++it) {
+ LOG(INFO, "removing client\n");
+ clients.erase(*it);
+ }
+ }
+ }
+};
+
+} // namespace camera
+} // namespace aos
+
+AOS_RUN_NRT(aos::camera::HTTPStreamer)
diff --git a/aos/atom_code/camera/Reader.cpp b/aos/atom_code/camera/Reader.cpp
new file mode 100644
index 0000000..9cfee2a
--- /dev/null
+++ b/aos/atom_code/camera/Reader.cpp
@@ -0,0 +1,362 @@
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <fcntl.h>
+#include <unistd.h>
+#include <errno.h>
+#include <malloc.h>
+#include <sys/stat.h>
+#include <sys/types.h>
+#include <sys/time.h>
+#include <sys/mman.h>
+
+#include <string>
+#include <inttypes.h>
+
+#include "aos/aos_core.h"
+#include "aos/atom_code/camera/V4L2.h"
+#include "aos/atom_code/camera/Buffers.h"
+
+#define CLEAR(x) memset(&(x), 0, sizeof(x))
+
+namespace aos {
+namespace camera {
+
+class Reader {
+ static const char *const dev_name;
+
+ // of the camera
+ int fd_;
+ // the bound socket listening for fd requests
+ int server_fd_;
+
+ static const aos_type_sig kRecycleSignature;
+ aos_queue *queue_, *recycle_queue_;
+ // the number of buffers currently queued in v4l2
+ uint32_t queued_;
+ public:
+ Reader() {
+ struct stat st;
+ if (stat(dev_name, &st) == -1) {
+ LOG(FATAL, "Cannot identify '%s' because of %d: %s\n",
+ dev_name, errno, strerror(errno));
+ }
+ if (!S_ISCHR(st.st_mode)) {
+ LOG(FATAL, "%s is no device\n", dev_name);
+ }
+
+ fd_ = open(dev_name, O_RDWR /* required */ | O_NONBLOCK, 0);
+ if (fd_ == -1) {
+ LOG(FATAL, "Cannot open '%s' because of %d: %s\n",
+ dev_name, errno, strerror(errno));
+ }
+
+ queue_ = aos_fetch_queue_recycle(Buffers::kQueueName.c_str(), &Buffers::kSignature,
+ &kRecycleSignature, &recycle_queue_);
+ // read off any existing recycled messages
+ while (aos_queue_read_msg(recycle_queue_, NON_BLOCK) != NULL);
+ queued_ = 0;
+
+ InitServer();
+ Init();
+ }
+ private:
+ void InitServer() {
+ if (unlink(Buffers::kFDServerName.c_str()) == -1 && errno != ENOENT) {
+ LOG(WARNING, "unlink(kFDServerName(='%s')) failed with %d: %s\n",
+ Buffers::kFDServerName.c_str(), errno, strerror(errno));
+ }
+ if ((server_fd_ = Buffers::CreateSocket(bind)) == -1) {
+ LOG(FATAL, "creating the IPC socket failed\n");
+ }
+ if (listen(server_fd_, 10) == -1) {
+ LOG(FATAL, "listen(%d, 10) failed with %d: %s\n",
+ server_fd_, errno, strerror(errno));
+ }
+ }
+ void SendFD(const int sock) {
+ int myfds[Buffers::kNumFDs]; /* Contains the file descriptors to pass. */
+ myfds[0] = fd_;
+ char buf[CMSG_SPACE(sizeof(myfds))]; /* ancillary data buffer */
+
+ iovec data;
+ memset(&data, 0, sizeof(data));
+ char dummy = 'A';
+ data.iov_base = &dummy;
+ data.iov_len = sizeof(dummy);
+ msghdr msg;
+ memset(&msg, 0, sizeof(msg));
+ msg.msg_iov = &data;
+ msg.msg_iovlen = 1;
+ msg.msg_control = buf;
+ msg.msg_controllen = sizeof(buf);
+ cmsghdr *const cmsg = CMSG_FIRSTHDR(&msg);
+ cmsg->cmsg_level = SOL_SOCKET;
+ cmsg->cmsg_type = SCM_RIGHTS;
+ cmsg->cmsg_len = CMSG_LEN(sizeof(myfds));
+ /* Initialize the payload: */
+ memcpy(CMSG_DATA(cmsg), myfds, sizeof(myfds));
+ if (sendmsg(sock, &msg, 0) == -1) {
+ LOG(ERROR, "sendmsg(%d, %p, 0) failed with %d: %s\n",
+ sock, &msg, errno, strerror(errno));
+ }
+ // leave it open so that the other end can tell if this process dies
+ }
+
+#if 0
+ // if we ever do want to do any of these things, this is how
+ void Stop() {
+ const v4l2_buf_type type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+ if (xioctl(fd_, VIDIOC_STREAMOFF, &type) == -1) {
+ errno_exit("VIDIOC_STREAMOFF");
+ }
+ }
+ void Close() {
+ if (close(fd_) == -1)
+ errno_exit("close");
+ fd_ = -1;
+ }
+#endif
+
+ void QueueBuffer(v4l2_buffer *buf) {
+ if (xioctl(fd_, VIDIOC_QBUF, buf) == -1) {
+ LOG(WARNING, "ioctl VIDIOC_QBUF(%d, %p) failed with %d: %s. losing buf #%"PRIu32"\n",
+ fd_, &buf, errno, strerror(errno), buf->index);
+ } else {
+ LOG(DEBUG, "put buf #%"PRIu32" into driver's queue\n", buf->index);
+ ++queued_;
+ }
+ }
+ void ReadFrame() {
+ v4l2_buffer buf;
+ CLEAR(buf);
+ buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+ buf.memory = V4L2_MEMORY_MMAP;
+
+ const Buffers::Message *read;
+ do {
+ read = static_cast<const Buffers::Message *>(
+ // we block waiting for one if we can't dequeue one without leaving
+ // the driver <= 2 (to be safe)
+ aos_queue_read_msg(recycle_queue_, (queued_ <= 2) ? BLOCK : NON_BLOCK));
+ if (read != NULL) {
+ buf.index = read->index;
+ aos_queue_free_msg(recycle_queue_, read);
+ QueueBuffer(&buf);
+ }
+ } while (read != NULL);
+
+ if (xioctl(fd_, VIDIOC_DQBUF, &buf) == -1) {
+ if (errno != EAGAIN) {
+ LOG(ERROR, "ioctl VIDIOC_DQBUF(%d, %p) failed with %d: %s\n",
+ fd_, &buf, errno, strerror(errno));
+ }
+ return;
+ }
+ --queued_;
+ if (buf.index >= Buffers::kNumBuffers) {
+ LOG(ERROR, "buf.index (%"PRIu32") is >= kNumBuffers (%u)\n",
+ buf.index, Buffers::kNumBuffers);
+ return;
+ }
+
+ Buffers::Message *const msg = static_cast<Buffers::Message *>(
+ aos_queue_get_msg(queue_));
+ if (msg == NULL) {
+ LOG(WARNING, "couldn't get a message to send buf #%"PRIu32" from queue %p."
+ " re-queueing now\n", buf.index, queue_);
+ QueueBuffer(&buf);
+ return;
+ }
+ msg->index = buf.index;
+ msg->bytesused = buf.bytesused;
+ memcpy(&msg->timestamp, &buf.timestamp, sizeof(msg->timestamp));
+ msg->sequence = buf.sequence;
+ if (aos_queue_write_msg_free(queue_, msg, OVERRIDE) == -1) {
+ LOG(WARNING, "sending message %p with buf #%"PRIu32" to queue %p failed."
+ " re-queueing now\n", msg, buf.index, queue_);
+ QueueBuffer(&buf);
+ return;
+ } else {
+ LOG(DEBUG, "sent message off to queue %p with buffer #%"PRIu32"\n",
+ queue_, buf.index);
+ }
+ }
+
+ void init_mmap() {
+ v4l2_requestbuffers req;
+ CLEAR(req);
+ req.count = Buffers::kNumBuffers;
+ req.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+ req.memory = V4L2_MEMORY_MMAP;
+ if (xioctl(fd_, VIDIOC_REQBUFS, &req) == -1) {
+ if (EINVAL == errno) {
+ LOG(FATAL, "%s does not support memory mapping\n", dev_name);
+ } else {
+ LOG(FATAL, "ioctl VIDIOC_REQBUFS(%d, %p) failed with %d: %s\n",
+ fd_, &req, errno, strerror(errno));
+ }
+ }
+ queued_ = Buffers::kNumBuffers;
+ if (req.count < Buffers::kNumBuffers) {
+ LOG(FATAL, "Insufficient buffer memory on %s\n", dev_name);
+ }
+ }
+
+ void Init() {
+ v4l2_capability cap;
+ if (xioctl(fd_, VIDIOC_QUERYCAP, &cap) == -1) {
+ if (EINVAL == errno) {
+ LOG(FATAL, "%s is no V4L2 device\n",
+ dev_name);
+ } else {
+ LOG(FATAL, "ioctl VIDIOC_QUERYCAP(%d, %p) failed with %d: %s\n",
+ fd_, &cap, errno, strerror(errno));
+ }
+ }
+ if (!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE)) {
+ LOG(FATAL, "%s is no video capture device\n",
+ dev_name);
+ }
+ if (!(cap.capabilities & V4L2_CAP_STREAMING)) {
+ LOG(FATAL, "%s does not support streaming i/o\n",
+ dev_name);
+ }
+
+ /* Select video input, video standard and tune here. */
+
+ v4l2_cropcap cropcap;
+ CLEAR(cropcap);
+ cropcap.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+ if (xioctl(fd_, VIDIOC_CROPCAP, &cropcap) == 0) {
+ v4l2_crop crop;
+ crop.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+ crop.c = cropcap.defrect; /* reset to default */
+
+ if (xioctl(fd_, VIDIOC_S_CROP, &crop) == -1) {
+ switch (errno) {
+ case EINVAL:
+ /* Cropping not supported. */
+ break;
+ default:
+ /* Errors ignored. */
+ break;
+ }
+ }
+ } else {
+ /* Errors ignored. */
+ }
+
+ v4l2_format fmt;
+ CLEAR(fmt);
+ fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+ fmt.fmt.pix.width = Buffers::kWidth;
+ fmt.fmt.pix.height = Buffers::kHeight;
+ fmt.fmt.pix.pixelformat = V4L2_PIX_FMT_MJPEG;
+ fmt.fmt.pix.field = V4L2_FIELD_ANY;
+ //fmt.fmt.pix.pixelformat = V4L2_PIX_FMT_YUYV;
+ //fmt.fmt.pix.field = V4L2_FIELD_INTERLACED;
+ if (xioctl(fd_, VIDIOC_S_FMT, &fmt) == -1) {
+ LOG(FATAL, "ioctl VIDIC_S_FMT(%d, %p) failed with %d: %s\n",
+ fd_, &fmt, errno, strerror(errno));
+ }
+ /* Note VIDIOC_S_FMT may change width and height. */
+
+ /* Buggy driver paranoia. */
+ unsigned int min = fmt.fmt.pix.width * 2;
+ if (fmt.fmt.pix.bytesperline < min)
+ fmt.fmt.pix.bytesperline = min;
+ min = fmt.fmt.pix.bytesperline * fmt.fmt.pix.height;
+ if (fmt.fmt.pix.sizeimage < min)
+ fmt.fmt.pix.sizeimage = min;
+
+#if 0
+ // set framerate
+ struct v4l2_streamparm *setfps;
+ setfps = (struct v4l2_streamparm *) calloc(1, sizeof(struct v4l2_streamparm));
+ memset(setfps, 0, sizeof(struct v4l2_streamparm));
+ setfps->type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+ setfps->parm.capture.timeperframe.numerator = 1;
+ setfps->parm.capture.timeperframe.denominator = 20;
+ if (xioctl(fd_, VIDIOC_S_PARM, setfps) == -1) {
+ LOG(ERROR, "ioctl VIDIOC_S_PARM(%d, %p) failed with %d: %s\n",
+ fd_, setfps, errno, strerror(errno));
+ exit(EXIT_FAILURE);
+ }
+ LOG(INFO, "framerate ended up at %d/%d\n",
+ setfps->parm.capture.timeperframe.numerator,
+ setfps->parm.capture.timeperframe.denominator);
+#endif
+
+ init_mmap();
+ }
+
+ void Start() {
+ LOG(DEBUG, "queueing buffers for the first time\n");
+ v4l2_buffer buf;
+ for (unsigned int i = 0; i < Buffers::kNumBuffers; ++i) {
+ CLEAR(buf);
+ buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+ buf.memory = V4L2_MEMORY_MMAP;
+ buf.index = i;
+ QueueBuffer(&buf);
+ }
+ LOG(DEBUG, "done with first queue\n");
+
+ v4l2_buf_type type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+ if (xioctl(fd_, VIDIOC_STREAMON, &type) == -1) {
+ LOG(FATAL, "ioctl VIDIOC_STREAMON(%d, %p) failed with %d: %s\n",
+ fd_, &type, errno, strerror(errno));
+ }
+ }
+
+ public:
+ void Run() {
+ Start();
+
+ fd_set fds;
+ timeval tv;
+ while (true) {
+ // HAVE TO DO THIS EACH TIME THROUGH THE LOOP
+ tv.tv_sec = 2;
+ tv.tv_usec = 0;
+
+ FD_ZERO(&fds);
+ FD_SET(fd_, &fds);
+ FD_SET(server_fd_, &fds);
+ switch (select(std::max(fd_, server_fd_) + 1, &fds, NULL, NULL, &tv)) {
+ case -1:
+ if (errno != EINTR) {
+ LOG(ERROR, "select(%d, %p, NULL, NULL, %p) failed with %d: %s\n",
+ std::max(fd_, server_fd_) + 1, &fds, &tv, errno, strerror(errno));
+ }
+ continue;
+ case 0:
+ LOG(WARNING, "select timed out\n");
+ continue;
+ }
+
+ if (FD_ISSET(fd_, &fds)) {
+ ReadFrame();
+ }
+ if (FD_ISSET(server_fd_, &fds)) {
+ const int sock = accept4(server_fd_, NULL, NULL, SOCK_NONBLOCK);
+ if (sock == -1) {
+ LOG(ERROR, "accept4(%d, NULL, NULL, SOCK_NONBLOCK(=%d) failed with %d: %s\n",
+ server_fd_, SOCK_NONBLOCK, errno, strerror(errno));
+ } else {
+ SendFD(sock);
+ }
+ }
+ }
+ }
+};
+const char *const Reader::dev_name = "/dev/video0";
+const aos_type_sig Reader::kRecycleSignature{
+ sizeof(Buffers::Message), 1, Buffers::kNumBuffers};
+
+} // namespace camera
+} // namespace aos
+
+AOS_RUN_NRT(aos::camera::Reader)
+
diff --git a/aos/atom_code/camera/V4L2.h b/aos/atom_code/camera/V4L2.h
new file mode 100644
index 0000000..bbafe3e
--- /dev/null
+++ b/aos/atom_code/camera/V4L2.h
@@ -0,0 +1,27 @@
+#ifndef AOS_ATOM_CODE_CAMREA_V4L2_H_
+#define AOS_ATOM_CODE_CAMREA_V4L2_H_
+
+// This file handles including everything needed to use V4L2 and has some
+// utility functions.
+
+#include <sys/ioctl.h>
+
+#include <asm/types.h> /* for videodev2.h */
+#include <linux/videodev2.h>
+
+namespace aos {
+namespace camera {
+
+static inline int xioctl(int fd, int request, void *arg) {
+ int r;
+ do {
+ r = ioctl(fd, request, reinterpret_cast<uintptr_t>(arg));
+ } while (r == -1 && errno == EINTR);
+ return r;
+}
+
+} // namespace camera
+} // namespace aos
+
+#endif
+
diff --git a/aos/atom_code/camera/aos.jar_manifest b/aos/atom_code/camera/aos.jar_manifest
new file mode 100644
index 0000000..8b13789
--- /dev/null
+++ b/aos/atom_code/camera/aos.jar_manifest
@@ -0,0 +1 @@
+
diff --git a/aos/atom_code/camera/camera.gyp b/aos/atom_code/camera/camera.gyp
new file mode 100644
index 0000000..e94a6ac
--- /dev/null
+++ b/aos/atom_code/camera/camera.gyp
@@ -0,0 +1,66 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'aos_camera',
+ 'type': 'loadable_module',
+ 'sources': [
+ 'jni.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:aos_shared_lib',
+ '<(AOS)/common/network/network.gyp:socket_so',
+ '<(AOS)/common/common.gyp:timing_so',
+ '<(AOS)/atom_code/messages/messages.gyp:messages_so',
+ 'private_aos_camera_jar',
+ '<(EXTERNALS):libjpeg',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/build/aos.gyp:aos_shared_lib',
+ '<(AOS)/common/network/network.gyp:socket_so',
+ '<(AOS)/common/common.gyp:timing_so',
+ '<(AOS)/atom_code/messages/messages.gyp:messages_so',
+ 'private_aos_camera_jar',
+ ],
+ },
+ {
+ 'target_name': 'private_aos_camera_jar',
+ 'dependencies': [
+ '<(EXTERNALS):javacv',
+ ],
+ 'variables': {
+ 'srcdirs': ['java'],
+ 'gen_headers': ['aos.Natives'],
+ },
+ 'export_dependent_settings': [
+ '<(EXTERNALS):javacv',
+ ],
+ 'direct_dependent_settings': {
+ 'variables': {
+ 'jni_libs': ['aos_camera'],
+ },
+ },
+ 'includes': ['../../build/java.gypi'],
+ 'hard_dependency': 1,
+ },
+ {
+ 'target_name': 'CameraHTTPStreamer',
+ 'type': 'executable',
+ 'sources': [
+ 'HTTPStreamer.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ {
+ 'target_name': 'CameraReader',
+ 'type': 'executable',
+ 'sources': [
+ 'Reader.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ ],
+}
diff --git a/aos/atom_code/camera/java/aos/CameraProcessor.java b/aos/atom_code/camera/java/aos/CameraProcessor.java
new file mode 100644
index 0000000..4f6c68d
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/CameraProcessor.java
@@ -0,0 +1,67 @@
+package aos;
+
+import java.io.IOException;
+import java.net.Inet4Address;
+import java.net.InetSocketAddress;
+import java.net.UnknownHostException;
+import java.nio.ByteBuffer;
+import java.nio.channels.ReadableByteChannel;
+import java.nio.channels.SocketChannel;
+import java.util.logging.Level;
+import java.util.logging.Logger;
+
+import com.googlecode.javacv.cpp.opencv_core;
+
+/**
+ * Makes implementing code that processes frames from a camera easy.
+ */
+public abstract class CameraProcessor {
+ private static final Logger LOG = Logger.getLogger(CameraProcessor.class.getName());
+ protected final ImageGetter getter;
+ protected final ServableImage start = new ServableImage(ImageGetter.width, ImageGetter.height, opencv_core.IPL_DEPTH_8U, 3);
+
+ /**
+ * Parses any arguments it recognizes out of {@code args} and initializes stuff appropriately.
+ * This includes using {@link QueueLogHandler} for all exceptions and {@link Thread#setDefaultUncaughtExceptionHandler}ing.
+ * @param args from {@code main}
+ */
+ protected CameraProcessor(String[] args) throws UnknownHostException, IOException {
+ QueueLogHandler.UseForAll();
+ ReadableByteChannel channel = null;
+ for (int i = 0; i < args.length; ++i) {
+ final String c = args[i];
+ if (c.equals("--host")) {
+ String host = args[++i];
+ final SocketChannel socketChannel = SocketChannel.open(new InetSocketAddress(Inet4Address.getByName(host), 9714));
+ socketChannel.write(ByteBuffer.wrap(new byte[] {'\r', '\n', '\r', '\n'})); // get it past the read headers stage
+ channel = socketChannel;
+ } else {
+ System.err.println("CameraProcessor: warning: unrecognized argument '" + c + "'. ignoring");
+ }
+ }
+
+ if (channel != null) {
+ getter = new ChannelImageGetter(channel);
+ } else {
+ System.out.println("creating QueueImageGetter");
+ getter = new QueueImageGetter();
+ System.out.println("done");
+ }
+
+ LOG.log(Level.INFO, "CameraProcessor is up");
+ System.err.println("CameraProcessor is up (on stderr)");
+ }
+
+ protected abstract void RunIteration();
+
+ protected void Run() {
+ while (true) {
+ if (!getter.get(start.getImage())) {
+ LOG.log(Level.WARNING, "getting image failed");
+ continue;
+ }
+ RunIteration();
+ start.releaseImage();
+ }
+ }
+}
diff --git a/aos/atom_code/camera/java/aos/ChannelImageGetter.java b/aos/atom_code/camera/java/aos/ChannelImageGetter.java
new file mode 100644
index 0000000..511b55b
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/ChannelImageGetter.java
@@ -0,0 +1,158 @@
+package aos;
+
+import java.io.IOException;
+import java.nio.ByteBuffer;
+import java.nio.channels.ReadableByteChannel;
+import java.nio.channels.SelectableChannel;
+import java.nio.channels.SelectionKey;
+import java.nio.channels.Selector;
+import java.util.Map;
+import java.util.TreeMap;
+import java.util.logging.Level;
+import java.util.logging.Logger;
+
+/**
+ * Retrieves images from a {@link InputChannel}. Expects the images in mjpg form.
+ * For now, only accepts streams formatted pretty closely to how aos::camera::HTTPStreamer does it.
+ */
+public class ChannelImageGetter extends JPEGImageGetter {
+ /**
+ * What to multiply each length by when it needs to allocate a larger buffer to fit an image.
+ */
+ private static final double extraLength = 1.2;
+
+ private static final Logger LOG = Logger.getLogger(ChannelImageGetter.class
+ .getName());
+ private final ReadableByteChannel channel;
+ private final Selector selector = Selector.open();
+ private String separator = "--boundarydonotcross\r\n";
+ private ByteBuffer current;
+ private final ByteBuffer headerBuffer = ByteBuffer.allocateDirect(30);
+ private final Map<String, String> headers = new TreeMap<String, String>(String.CASE_INSENSITIVE_ORDER);
+
+ public ChannelImageGetter(ReadableByteChannel channel) throws IOException {
+ this.channel = channel;
+ if (channel instanceof SelectableChannel) {
+ ((SelectableChannel)channel).configureBlocking(false);
+ }
+ }
+
+ @Override
+ public ByteBuffer getJPEG() {
+ try {
+ if (!parseHeaders()) {
+ return null;
+ }
+ LOG.log(Level.FINE, "parsed headers " + headers.toString());
+ try {
+ final int length = Integer.parseInt(headers.get("Content-Length"));
+ if (current == null || current.capacity() < length) {
+ LOG.log(Level.INFO, "allocating a new direct buffer of length " + length * extraLength);
+ current = ByteBuffer.allocateDirect((int) (length * extraLength));
+ } else {
+ current.rewind();
+ current.limit(length);
+ }
+ } catch (NumberFormatException e) {
+ LOG.log(Level.WARNING, "couldn't parse '" + headers.get("Content-Length") + "' as a number");
+ return null;
+ }
+ current.put(headerBuffer); // copy out any of the image that got buffered with the headers
+ while (current.hasRemaining()) {
+ channel.read(current);
+ }
+ current.flip();
+ } catch (IOException e) {
+ LOG.log(Level.WARNING, "reading the headers and/or image failed", e);
+ return null;
+ }
+ return current;
+ }
+ // returns success
+ private boolean parseHeaders() throws IOException {
+ // Reads chunks into headerBuffer and parses out headers.
+ // Looks for separator first.
+
+ headerBuffer.clear();
+ headers.clear();
+ final byte[] separatorBytes = separator.getBytes();
+ int separatorIndex = 0; // how much of the separator has been matched
+ while (headerBuffer.hasRemaining() || headerBuffer.limit() < headerBuffer.capacity()) {
+ if (channel instanceof SelectableChannel) {
+ ((SelectableChannel)channel).register(selector, SelectionKey.OP_READ);
+ selector.select();
+ }
+ headerBuffer.limit(headerBuffer.capacity());
+ channel.read(headerBuffer);
+ headerBuffer.flip();
+ if (separatorIndex < separatorBytes.length) {
+ // make sure we don't get part of the way through
+ while (headerBuffer.remaining() >= (separatorBytes.length - separatorIndex)) {
+ final byte c = headerBuffer.get();
+ if (separatorBytes[separatorIndex++] != c) {
+ separatorIndex = 0;
+ }
+ if (separatorIndex == separatorBytes.length) {
+ break;
+ }
+ }
+ headerBuffer.compact();
+ } else {
+ int keyEnd = 0, valueStart = 0;
+ boolean foundEndR = false; // found the end \r
+ while (headerBuffer.hasRemaining()) {
+ final byte c = headerBuffer.get();
+ if (foundEndR) {
+ if (c != '\n') {
+ LOG.log(Level.WARNING, "found \r\n\r but no \n afterwards");
+ } else {
+ return true;
+ }
+ } else if (keyEnd == 0) {
+ if (c == ':') {
+ keyEnd = headerBuffer.position() - 1;
+ } else if (c == '\r') {
+ foundEndR = true;
+ }
+ } else if (valueStart == 0) {
+ if (c != ' ') {
+ valueStart = headerBuffer.position() - 1;
+ }
+ } else {
+ if (c == '\r') {
+ final int valueEnd = headerBuffer.position();
+ final byte[] key = new byte[keyEnd];
+ headerBuffer.position(0);
+ headerBuffer.get(key);
+ final byte[] value = new byte[valueEnd - valueStart - 1];
+ headerBuffer.position(valueStart);
+ headerBuffer.get(value);
+ headers.put(new String(key), new String(value));
+
+ headerBuffer.get(); // get the \r
+ headerBuffer.get(); // get the \n
+
+ headerBuffer.compact();
+ headerBuffer.flip();
+
+ keyEnd = valueStart = 0;
+ }
+ }
+ }
+ }
+ }
+ // if we got here, then it doesn't have space left and we haven't finished
+ LOG.log(Level.WARNING, "got a header that was too long. headerBuffer should be made bigger");
+ return false;
+ }
+
+ @Override
+ public double getTimestamp() {
+ if (headers.containsKey("X-Timestamp")) {
+ return Double.parseDouble(headers.get("X-Timestamp"));
+ } else {
+ throw new UnsupportedOperationException("source stream doesn't have X-Timestamp headers");
+ }
+ }
+
+}
diff --git a/aos/atom_code/camera/java/aos/DebugServer.java b/aos/atom_code/camera/java/aos/DebugServer.java
new file mode 100644
index 0000000..398cb11
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/DebugServer.java
@@ -0,0 +1,357 @@
+package aos;
+
+import java.io.ByteArrayOutputStream;
+import java.io.IOException;
+import java.net.InetSocketAddress;
+import java.nio.ByteBuffer;
+import java.nio.ByteOrder;
+import java.nio.channels.ClosedChannelException;
+import java.nio.channels.SelectionKey;
+import java.nio.channels.Selector;
+import java.nio.channels.ServerSocketChannel;
+import java.nio.channels.SocketChannel;
+import java.util.ArrayList;
+import java.util.Collection;
+import java.util.HashMap;
+import java.util.Iterator;
+import java.util.Map;
+import java.util.logging.Level;
+import java.util.logging.Logger;
+import java.util.regex.Matcher;
+import java.util.regex.Pattern;
+
+import com.googlecode.javacv.cpp.opencv_core.IplImage;
+
+/**
+ * A server that serves {@link ServableImage}s.
+ */
+public class DebugServer {
+ private static final String initialHeaderString = "HTTP/1.0 200 OK\r\n"
+ + "Connection: close\r\n"
+ + "Server: AOS/0.0 Vision Code Debug\r\n"
+ + "Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, post-check=0, max-age=0\r\n"
+ + "Pragma: no-cache\r\n"
+ + "Expires: Mon, 3 Jan 2000 12:34:56 GMT\r\n"
+ + "Content-Type: multipart/x-mixed-replace; boundary=boundarydonotcross\r\n";
+ private static final String intermediateHeaderFormat = "\r\n--boundarydonotcross\r\n"
+ + "Content-Type: image/bmp\r\n"
+ + "Content-Length: %d\r\n"
+ + "X-Timestamp: %f\r\n"
+ + "\r\n";
+ private static final ByteBuffer initialHeader;
+ private static final Pattern headerPattern;
+ static {
+ initialHeader = ByteBuffer.wrap(initialHeaderString.getBytes())
+ .asReadOnlyBuffer();
+ headerPattern = Pattern.compile("^GET ([^? ]+)(?:\\?i=(\\S*))? HTTP/.*\r\n.*$",
+ Pattern.DOTALL);
+ }
+
+ private static final Logger LOG = Logger.getLogger(DebugServer.class
+ .getName());
+ private final ServerSocketChannel server;
+ private final Collection<Client> clients = new ArrayList<Client>();
+ private final Map<String, ServableImage> images = new HashMap<String, ServableImage>();
+ private final Map<String, Palette> palettes = new HashMap<String, Palette>();
+ private double timestamp;
+
+ public static class Palette {
+ private final ByteArrayOutputStream out = new ByteArrayOutputStream();
+ private int entries = 0;
+
+ /**
+ * Adds a new color. All 4 arguments are unsigned bytes.
+ * @param r red
+ * @param g green
+ * @param b blue
+ * @param a alpha (doesn't seem to work)
+ * @return this
+ */
+ public Palette add(int r, int g, int b, int a) {
+ out.write(b);
+ out.write(g);
+ out.write(r);
+ out.write(a);
+ ++entries;
+ return this;
+ }
+
+ private int entries() {
+ return entries;
+ }
+ private int bytes() {
+ return entries * 4;
+ }
+ private void writeTo(ByteBuffer buffer) {
+ buffer.put(out.toByteArray());
+ }
+ }
+
+ private class Client {
+ private final int bmpHeaderSize;
+ private int bmpType;
+ private Palette palette;
+
+ private final SocketChannel channel;
+ private ServableImage image = null;
+ private IplImage img;
+ private int index;
+ private final ByteBuffer[] buffers;
+ private final ByteBuffer initial = initialHeader.duplicate();
+ private final ByteBuffer read = ByteBuffer.allocate(1024);
+
+ public Client(SocketChannel channel) throws IOException {
+ this.channel = channel;
+ channel.configureBlocking(false);
+
+ if (bmpType == 3) {
+ bmpHeaderSize = 122;
+ } else if (bmpType == 0) {
+ bmpHeaderSize = 54;
+ } else {
+ throw new AssertionError("unknown bmpType value " + bmpType);
+ }
+ // [0] gets filled in by createBmpHeader which writes the header into [1]
+ // [2] gets set to the image buffer
+ buffers = new ByteBuffer[] { null, ByteBuffer.allocate(2048), null };
+ }
+
+ public void register(Selector selector) throws ClosedChannelException {
+ channel.register(
+ selector,
+ (image == null) ? SelectionKey.OP_READ
+ : SelectionKey.OP_WRITE, this);
+ }
+
+ public void close() {
+ if (image != null) {
+ image.setDebugging(false);
+ }
+ if (channel != null) {
+ try {
+ channel.close();
+ } catch (IOException e) {
+ LOG.log(Level.WARNING,
+ "encountered error when closing channel", e);
+ }
+ }
+ }
+
+ private void createBmpHeader(ByteBuffer buffer) {
+ // <http://en.wikipedia.org/wiki/BMP_file_format#File_structure>
+ // explains what these all are
+ // signed/unsigned numbers don't matter because they'd better not be
+ // that big
+ final int paletteSize = (palette == null) ? 0 : palette.bytes();
+ buffers[0] = ByteBuffer.wrap(String.format(intermediateHeaderFormat,
+ bmpHeaderSize + paletteSize + image.imageSize(), timestamp).getBytes());
+ buffer.order(ByteOrder.LITTLE_ENDIAN);
+ buffer.put((byte) 'B').put((byte) 'M');
+ buffer.putInt(bmpHeaderSize + paletteSize + image.imageSize());
+ buffer.putInt(0); // skip ahead 4 bytes
+ buffer.putInt(bmpHeaderSize + paletteSize); // offset to start of image data
+ buffer.putInt(bmpHeaderSize - 14); // size of the rest of the header
+ // BMPs expect image data bottom to top, so -height to fix that
+ buffer.putInt(ImageGetter.width).putInt(-ImageGetter.height);
+ buffer.putShort((short) 1).putShort(image.bitsPerPixel());
+ buffer.putInt(bmpType);
+ buffer.putInt(image.imageSize()); // number of bytes in the actual
+ // image
+ buffer.putInt(2835).putInt(2835); // physical resolution; don't
+ // think it matters
+ buffer.putInt((palette == null) ? 0 : palette.entries());
+ buffer.putInt(0); // # of important colors (0 means all)
+ if (palette != null) {
+ palette.writeTo(buffer);
+ }
+ final int expected;
+ if (bmpType == 0) { // BI_RGB
+ expected = bmpHeaderSize + paletteSize;
+ } else if (bmpType == 3) { // BI_BITFIELDS
+ buffer.putInt(0x0000FF00).putInt(0x00FF0000).putInt(0xFF000000)
+ .putInt(0); // RGBA bitmasks
+ buffer.putInt(0x57696E20); // LCS_WINDOWS_COLOR_SPACE
+ expected = bmpHeaderSize - 48;
+ } else {
+ throw new AssertionError("unknown bmpType value " + bmpType);
+ }
+ if (buffer.position() != expected) {
+ throw new AssertionError(
+ "header ended up the wrong size. expected "
+ + expected + " but got "
+ + buffer.position());
+ }
+ buffer.limit(bmpHeaderSize + paletteSize);
+ buffer.rewind();
+ }
+
+ /**
+ * Does anything that this one can right now.
+ *
+ * @return whether or not to {@link #close()} and remove this one
+ */
+ public boolean run() throws IOException {
+ if (image == null) {
+ final int bytesRead = channel.read(read);
+ final String readString = new String(read.array(), 0,
+ read.position());
+ LOG.log(Level.INFO, "read " + bytesRead
+ + " header bytes position=" + read.position()
+ + " string='" + readString + "'");
+
+ final Matcher matcher = headerPattern.matcher(readString);
+ if (matcher.matches()) {
+ final String url = matcher.group(1);
+ image = images.get(url);
+ if (image == null) {
+ LOG.log(Level.INFO, "couldn't find an image for url '"
+ + url + "'. dropping client");
+ return true;
+ } else {
+ LOG.log(Level.INFO, "found an image for url '"
+ + url + "'");
+ }
+ palette = palettes.get(url);
+ bmpType = 0; // could change this in the future
+ createBmpHeader(buffers[1]);
+ image.setDebugging(true);
+ final String indexString = matcher.group(2);
+ if (indexString != null) {
+ index = Integer.parseInt(indexString);
+ } else {
+ index = 0;
+ }
+ LOG.log(Level.INFO, "using index " + index);
+ } else if (!read.hasRemaining()) {
+ read.flip();
+ LOG.log(Level.WARNING,
+ "ran out of buffer space reading the header. currently have '"
+ + readString + "'. dropping connection");
+ return true;
+ } else if (bytesRead == -1) {
+ read.flip();
+ LOG.log(Level.WARNING,
+ "reached end of stream for headers without getting anything valid. currently have "
+ + read.limit()
+ + " bytes ='"
+ + readString
+ + "'. dropping connection");
+ return true;
+ }
+ } else if (initial.hasRemaining()) {
+ channel.write(initial);
+ } else {
+ if (buffers[2] == null) {
+ img = image.getSnapshot(index);
+ if (img == null) {
+ return false;
+ } else {
+ buffers[2] = img.getByteBuffer();
+ LOG.log(Level.FINE, "got " + buffers[2]
+ + " from the image");
+ }
+ }
+ channel.write(buffers);
+ boolean remaining = false;
+ for (ByteBuffer c : buffers) {
+ if (c.hasRemaining()) {
+ remaining = true;
+ }
+ }
+ if (!remaining) {
+ for (ByteBuffer c : buffers) {
+ c.rewind();
+ }
+ buffers[2] = null;
+ image.releaseSnapshot(index, img);
+ }
+ }
+ return false;
+ }
+ }
+
+ public DebugServer(int port) throws IOException {
+ server = ServerSocketChannel.open();
+ server.configureBlocking(false);
+ server.socket().bind(new InetSocketAddress(port), 10);
+ new Thread("DebugServer") {
+ @Override
+ public void run() {
+ try {
+ loop();
+ } catch (Throwable e) {
+ LOG.log(Level.SEVERE,
+ "trouble running the server loop", e);
+ System.exit(1);
+ }
+ }
+ }.start();
+ }
+
+ public void addImage(String name, ServableImage image) {
+ if (image.bitsPerPixel() != 24) {
+ throw new IllegalArgumentException("only 24-bit images are supported");
+ // could support 16 and 32 bpp images by using bmpType of 3
+ }
+ images.put(name, image);
+ }
+ public void addImage(String name, ServableImage image, Palette palette) {
+ if (image.bitsPerPixel() != 8) {
+ throw new IllegalArgumentException("only 8-bit images are supported");
+ // everything should work for 1, 2, and 4 bpp ones too except for padding etc
+ }
+ if (palette.entries() > (1 << image.bitsPerPixel())) {
+ throw new IllegalArgumentException("too many colors in the palette");
+ }
+ images.put(name, image);
+ palettes.put(name, palette);
+ }
+ /**
+ * This timestamp is written out in the debugging images.
+ * @param timestamp the current timestamp
+ */
+ public void setTimestamp(double timestamp) {
+ this.timestamp = timestamp;
+ }
+
+ private void loop() throws IOException {
+ final Selector selector = Selector.open();
+ server.register(selector, SelectionKey.OP_ACCEPT);
+ while (true) {
+ try {
+ for (Client c : clients) {
+ c.register(selector);
+ }
+ selector.select();
+ for (final Iterator<SelectionKey> i = selector.selectedKeys()
+ .iterator(); i.hasNext();) {
+ final SelectionKey c = i.next();
+ if (c.isAcceptable()) {
+ // there's only 1 socket there that can accept
+ final SocketChannel channel = server.accept();
+ if (channel != null) {
+ clients.add(new Client(channel));
+ }
+ } else {
+ final Client client = (Client) c.attachment();
+ try {
+ if (client.run()) {
+ client.close();
+ clients.remove(client);
+ }
+ } catch (Exception e) {
+ LOG.log(Level.INFO, "dropping client " + client
+ + " because it's run() threw an exception",
+ e);
+ client.close();
+ clients.remove(client);
+ }
+ }
+ i.remove();
+ }
+ } catch (IOException e) {
+ LOG.log(Level.WARNING, "trouble running the server loop", e);
+ }
+ }
+ }
+}
diff --git a/aos/atom_code/camera/java/aos/ImageGetter.java b/aos/atom_code/camera/java/aos/ImageGetter.java
new file mode 100644
index 0000000..f0f1063
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/ImageGetter.java
@@ -0,0 +1,24 @@
+package aos;
+
+import com.googlecode.javacv.cpp.opencv_core;
+import com.googlecode.javacv.cpp.opencv_core.IplImage;
+
+/**
+ * An object that can retrieve images from somewhere.
+ */
+public interface ImageGetter {
+ public static int width = 640, height = 480;
+
+ /**
+ * Gets an image.
+ * @param out Where to write the image to. Must be a 3-channel {@link opencv_core#IPL_DEPTH_8U} image.
+ * @return whether it succeeded or not
+ */
+ public boolean get(IplImage out);
+ /**
+ * Only valid after a successful {@link #get()}.
+ * @return The timestamp from the most recent frame. Will be in seconds with at least ms accuracy.
+ */
+ public double getTimestamp();
+}
+
diff --git a/aos/atom_code/camera/java/aos/JPEGDecoder.java b/aos/atom_code/camera/java/aos/JPEGDecoder.java
new file mode 100644
index 0000000..63d12fd
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/JPEGDecoder.java
@@ -0,0 +1,29 @@
+package aos;
+
+import java.nio.ByteBuffer;
+
+import com.googlecode.javacv.cpp.opencv_core;
+import com.googlecode.javacv.cpp.opencv_core.IplImage;
+
+/**
+ * Efficiently decodes a JPEG image from a @{class ByteBuffer} into an @{class IplImage}.
+ * Instances are not safe for use from multiple threads.
+ * The first use of an instance allocates some largish buffers which are never freed.
+ */
+public class JPEGDecoder {
+ private final long[] state = new long[1];
+
+ /**
+ * @param in Must be direct. The {@link ByteBuffer#limit()} of it will be respected.
+ * @param out Where to write the decoded image to. Must be a 3-channel {@link opencv_core#IPL_DEPTH_8U} image.
+ * Will be written in the RGB color space.
+ * @return Whether or not it succeeded. If not, {@code out} is undefined.
+ */
+ public boolean decode(ByteBuffer in, IplImage out) {
+ if (out.nChannels() != 3 || out.depth() != opencv_core.IPL_DEPTH_8U) {
+ throw new IllegalArgumentException("out is invalid");
+ }
+ return Natives.decodeJPEG(state, in, in.limit(), out.getByteBuffer());
+ }
+}
+
diff --git a/aos/atom_code/camera/java/aos/JPEGImageGetter.java b/aos/atom_code/camera/java/aos/JPEGImageGetter.java
new file mode 100644
index 0000000..84296e7
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/JPEGImageGetter.java
@@ -0,0 +1,26 @@
+package aos;
+
+import java.nio.ByteBuffer;
+
+import com.googlecode.javacv.cpp.opencv_core.IplImage;
+
+/**
+ * Helper class for {@link ImageGetter}s that return JPEG images.
+ */
+public abstract class JPEGImageGetter implements ImageGetter {
+
+ private final JPEGDecoder decoder = new JPEGDecoder();
+
+ @Override
+ public boolean get(IplImage out) {
+ final ByteBuffer jpeg = getJPEG();
+ if (jpeg == null) return false;
+ final boolean r = decoder.decode(jpeg, out);
+ release();
+ return r;
+ }
+
+ protected abstract ByteBuffer getJPEG();
+ protected void release() {}
+
+}
diff --git a/aos/atom_code/camera/java/aos/JavaCVImageGetter.java b/aos/atom_code/camera/java/aos/JavaCVImageGetter.java
new file mode 100644
index 0000000..67398f0
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/JavaCVImageGetter.java
@@ -0,0 +1,56 @@
+package aos;
+
+import java.util.logging.Level;
+import java.util.logging.Logger;
+
+import com.googlecode.javacv.FrameGrabber;
+import com.googlecode.javacv.cpp.opencv_core.IplImage;
+
+
+/**
+ * Adapts between the JavaCV {@link FrameGrabber} and {@link ImageGetter}.
+ * There is (at least) 1 extra copy involved, so this shouldn't be used if you care about speed.
+ */
+public class JavaCVImageGetter implements ImageGetter {
+ private static final Logger LOG = Logger.getLogger(JavaCVImageGetter.class
+ .getName());
+ private final FrameGrabber grabber;
+
+ public JavaCVImageGetter(FrameGrabber grabber) {
+ this.grabber = grabber;
+ if (grabber.getImageWidth() != width || grabber.getImageHeight() != height) {
+ if (grabber.getImageWidth() == 0 && grabber.getImageHeight() == 0) {
+ LOG.log(Level.WARNING, "grabber says it will give 0x0 images at the start. ignoring");
+ } else {
+ throw new IllegalArgumentException("grabber says it will give images that are the wrong size!!");
+ }
+ }
+ }
+
+ @Override
+ public boolean get(IplImage out) {
+ try {
+ final IplImage frame = grabber.grab();
+ if (grabber.getImageWidth() != width || grabber.getImageHeight() != height) {
+ LOG.log(Level.SEVERE, "grabber says it will give the wrong size images");
+ return false;
+ }
+ if (out.imageSize() != frame.imageSize()) {
+ LOG.log(Level.SEVERE, "the grabber gave a " + frame.imageSize() + "-byte image" +
+ "but a " + out.imageSize() + "-byte image was passed in");
+ return false;
+ }
+ out.getByteBuffer().put(frame.getByteBuffer());
+ return true;
+ } catch (FrameGrabber.Exception e) {
+ LOG.log(Level.WARNING, "grabber.grab() threw an exception", e);
+ return false;
+ }
+ }
+
+ @Override
+ public double getTimestamp() {
+ // grabber.getTimestamp seems to be in ms (all the implementations are at least)
+ return grabber.getTimestamp() / 1000.0;
+ }
+}
diff --git a/aos/atom_code/camera/java/aos/NativeBufferError.java b/aos/atom_code/camera/java/aos/NativeBufferError.java
new file mode 100644
index 0000000..41c794d
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/NativeBufferError.java
@@ -0,0 +1,22 @@
+package aos;
+
+public class NativeBufferError extends NativeError {
+ private static final long serialVersionUID = -5298480149664213316L;
+
+ public NativeBufferError() {
+ super();
+ }
+
+ public NativeBufferError(String message, Throwable cause) {
+ super(message, cause);
+ }
+
+ public NativeBufferError(String message) {
+ super(message);
+ }
+
+ public NativeBufferError(Throwable cause) {
+ super(cause);
+ }
+
+}
diff --git a/aos/atom_code/camera/java/aos/NativeError.java b/aos/atom_code/camera/java/aos/NativeError.java
new file mode 100644
index 0000000..d410234
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/NativeError.java
@@ -0,0 +1,25 @@
+package aos;
+
+/**
+ * Represents an error from native code.
+ */
+public class NativeError extends Error {
+ private static final long serialVersionUID = 7394872852984037261L;
+
+ public NativeError() {
+ super();
+ }
+
+ public NativeError(String message, Throwable cause) {
+ super(message, cause);
+ }
+
+ public NativeError(String message) {
+ super(message);
+ }
+
+ public NativeError(Throwable cause) {
+ super(cause);
+ }
+
+}
diff --git a/aos/atom_code/camera/java/aos/NativeLoader.java b/aos/atom_code/camera/java/aos/NativeLoader.java
new file mode 100644
index 0000000..d4fe7a8
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/NativeLoader.java
@@ -0,0 +1,14 @@
+package aos;
+
+/**
+ * Provides support for dealing with loading native code.
+ */
+public class NativeLoader {
+ /**
+ * Loads a native library.
+ * @param name the name of the gyp shared_library or loadable_module target to load
+ */
+ public static void load(String name) {
+ System.load(System.getProperty("one-jar.expand.dir") + "/so_libs/lib" + name + ".so");
+ }
+}
diff --git a/aos/atom_code/camera/java/aos/Natives.java b/aos/atom_code/camera/java/aos/Natives.java
new file mode 100644
index 0000000..8ea4e01
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/Natives.java
@@ -0,0 +1,82 @@
+package aos;
+
+import com.googlecode.javacv.cpp.opencv_core;
+
+import java.nio.ByteBuffer;
+import java.util.logging.Level;
+
+/**
+ * <p>Package-private class that has all of the native functions in it to make them easier to implement.</p>
+ * <p>WARNING: The raw native functions are <b>NOT</b> thread-safe!!!!! Any java functions that need to be thread safe MUST be synchronized in JAVA!</p>
+ */
+class Natives {
+ static {
+ NativeLoader.load("aos_camera");
+ nativeInit(ImageGetter.width, ImageGetter.height);
+ }
+ private static native void nativeInit(int width, int height);
+ /**
+ * Empty function to make sure the class gets loaded (which means loading the native library).
+ */
+ public static void ensureLoaded() {}
+
+ /**
+ * Decodes a JPEG from in into out. Both buffers must be direct.
+ * @param state a long[1] for storing thread-local state
+ * @param in the JPEG to decode
+ * @param inBytes how many bytes long the JPEG is
+ * @param out the buffer to write the decoded image into
+ * @return Whether or not it succeeded. If not, {@code out} is undefined.
+ */
+ public static native boolean decodeJPEG(long[] state, ByteBuffer in, int inBytes, ByteBuffer out);
+
+ /**
+ * Thresholds in into out. Both buffers must be direct.
+ * All of the short arguments should be unsigned bytes. The min and max parameters specify what colors to accept.
+ * @param in The image to threshold. Must be a 3-channel {@link opencv_core#IPL_DEPTH_8U} image buffer in the HSV color space.
+ * @param out Where to write the thresholded image to. Must be a 1-channel {@link opencv_core#IPL_DEPTH_8U} image buffer.
+ * @param hoffset An offset to be added to the hue value before comparing it to {@code hmin} and {@code hmax}.
+ * The addition will be performed to a {@code uint8_t}, which will wrap around. This means that it must be positive.
+ * Useful for finding red values.
+ */
+ public static native void threshold(ByteBuffer in, ByteBuffer out, short hoffset, char hmin, char hmax,
+ char smin, char smax, char vmin, char vmax);
+
+ /**
+ * Converts the colors from in to the format required for dumping them into a BMP image.
+ * @param in The image to convert. Must be a 3-channel {@link opencv_core#IPL_DEPTH_8U} image buffer in the regular (BGR I think...) color space.
+ * @param out Where to write the converted image to. Must be a 3-channel {@link opencv_core#IPL_DEPTH_8U} image buffer.
+ */
+ public static native void convertBGR2BMP(ByteBuffer in, ByteBuffer out);
+
+ /**
+ * Retrieves a JPEG image from the queue system. Will block until a new one is ready.
+ * @param id from {@link #queueInit()}
+ * @return Will be direct. This buffer <b>must not EVER</b> be written to.
+ */
+ public static native ByteBuffer queueGetJPEG(long id);
+ /**
+ * Retrieves the latest frame timestamp from the queue system. Must only be called between {@link #queueGetJPEG} and {@link #queueReleaseJPEG}.
+ * @param id from {@link #queueInit()}
+ * @return a timestamp
+ */
+ public static native double queueGetTimestamp(long id);
+ /**
+ * Releases the last image retrieved from the queue system. The result of the last {@link #queueGetJPEG()} will now be invalid.
+ * @param id from {@link #queueInit()}
+ */
+ public static native void queueReleaseJPEG(long id);
+ /**
+ * Prepares to start retrieving JPEGs from the queues.
+ * @return the ID to pass to the other queue functions
+ */
+ public static native long queueInit();
+
+ /**
+ * Puts the given message into the logging framework.
+ * @param message the complete log message
+ * @param level the level (from {@link Level#intValue()}
+ */
+ public static native void LOG(String message, int level);
+}
+
diff --git a/aos/atom_code/camera/java/aos/QueueImageGetter.java b/aos/atom_code/camera/java/aos/QueueImageGetter.java
new file mode 100644
index 0000000..7ed2f65
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/QueueImageGetter.java
@@ -0,0 +1,34 @@
+package aos;
+
+import java.nio.ByteBuffer;
+
+/**
+ * Retrieves images from the queue system.<br>
+ * {@link #getTimestamp()} returns the value from the v4l2 driver,
+ * which is a CLOCK_MONOTONIC time for most (all?) of them and definitely uvcvideo.
+ */
+public class QueueImageGetter extends JPEGImageGetter {
+ private final long nativeID;
+ public QueueImageGetter() {
+ nativeID = Natives.queueInit();
+ }
+
+ @Override
+ public ByteBuffer getJPEG() {
+ final ByteBuffer buf = Natives.queueGetJPEG(nativeID);
+ if (buf == null) {
+ return null;
+ }
+ return buf.asReadOnlyBuffer();
+ }
+
+ @Override
+ public void release() {
+ Natives.queueReleaseJPEG(nativeID);
+ }
+
+ @Override
+ public double getTimestamp() {
+ return Natives.queueGetTimestamp(nativeID);
+ }
+}
diff --git a/aos/atom_code/camera/java/aos/QueueLogHandler.java b/aos/atom_code/camera/java/aos/QueueLogHandler.java
new file mode 100644
index 0000000..3eb8938
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/QueueLogHandler.java
@@ -0,0 +1,119 @@
+package aos;
+
+import java.lang.Thread.UncaughtExceptionHandler;
+import java.util.logging.Formatter;
+import java.util.logging.Handler;
+import java.util.logging.Level;
+import java.util.logging.LogRecord;
+import java.util.logging.Logger;
+import java.util.logging.SimpleFormatter;
+
+/**
+ * <p>Sends messages to the AOS queue-based logging system. Also sends anything that's at least a {@link Level#WARNING} to {@link System#err}.</p>
+ * <p>Writes out each stack frame of exceptions as a separate line after the first one with a \t at the beginning.</p>
+ */
+public class QueueLogHandler extends Handler {
+ private Formatter defaultFormatter;
+
+ /**
+ * Sets up the logging framework to use an instance of this class for all logging and returns the newly created instance.
+ */
+ public static QueueLogHandler UseForAll() {
+ Natives.ensureLoaded();
+ final Logger top = Logger.getLogger("");
+ for (Handler c : top.getHandlers()) {
+ top.removeHandler(c);
+ }
+ QueueLogHandler instance = new QueueLogHandler();
+ top.addHandler(instance);
+ top.setLevel(Level.ALL);
+
+ Thread.setDefaultUncaughtExceptionHandler(new UncaughtExceptionHandler() {
+ @Override
+ public void uncaughtException(Thread thread, Throwable e) {
+ top.log(Level.SEVERE, "uncaught exception in thread " + thread, e);
+ System.exit(1);
+ }
+ });
+
+ return instance;
+ }
+
+ @Override
+ public void close() throws SecurityException {
+ }
+ @Override
+ public void flush() {
+ }
+
+ private Formatter findFormatter() {
+ final Formatter r = getFormatter();
+ if (r != null) {
+ return r;
+ }
+ if (defaultFormatter != null) {
+ return defaultFormatter;
+ }
+ return defaultFormatter = new SimpleFormatter();
+ }
+ @Override
+ public void publish(LogRecord record) {
+ /*final StringBuilder thrownString = new StringBuilder(0);
+ if (record.getThrown() != null) {
+ thrownString.append(": ");
+ thrownString.append(record.getThrown().toString());
+ for (StackTraceElement c : record.getThrown().getStackTrace()) {
+ thrownString.append(" > ");
+ thrownString.append(c.getClassName());
+ thrownString.append('.');
+ thrownString.append(c.getMethodName());
+ thrownString.append('(');
+ thrownString.append(c.getFileName());
+ thrownString.append(':');
+ thrownString.append(c.getLineNumber());
+ thrownString.append(')');
+ }
+ }
+ Natives.LOG(record.getSourceClassName() + ": " + record.getSourceMethodName() + ": " +
+ findFormatter().formatMessage(record) + thrownString, record.getLevel().intValue());*/
+ if (record.getThrown() instanceof UnsatisfiedLinkError || record.getThrown().getCause() instanceof UnsatisfiedLinkError) {
+ record.setThrown(new UnsatisfiedLinkError("are you running a JVM of the correct bitness?").initCause(record.getThrown()));
+ }
+ Natives.LOG(record.getSourceClassName() + ": " + record.getSourceMethodName() + ": " +
+ findFormatter().formatMessage(record), record.getLevel().intValue());
+ if (record.getThrown() != null) {
+ logException(record.getThrown(), record.getLevel().intValue(), false);
+ }
+
+ if (record.getLevel().intValue() >= Level.WARNING.intValue()) {
+ System.err.println(findFormatter().format(record));
+ }
+ }
+ private void logException(Throwable e, int level, boolean caused_by) {
+ final StringBuilder thrownString = new StringBuilder();
+ if (caused_by) {
+ thrownString.append("Caused by: ");
+ }
+ thrownString.append(e.getClass().getName());
+ thrownString.append(": ");
+ thrownString.append(e.getLocalizedMessage());
+ Natives.LOG(thrownString.toString(), level);
+ for (StackTraceElement c : e.getStackTrace()) {
+ thrownString.setLength(0);
+ thrownString.append("\t");
+ thrownString.append(c.getClassName());
+ thrownString.append('.');
+ thrownString.append(c.getMethodName());
+ thrownString.append('(');
+ thrownString.append(c.getFileName());
+ thrownString.append(':');
+ thrownString.append(c.getLineNumber());
+ thrownString.append(')');
+ Natives.LOG(thrownString.toString(), level);
+ }
+ if (e.getCause() != null) {
+ logException(e.getCause(), level, true);
+ }
+ }
+
+}
diff --git a/aos/atom_code/camera/java/aos/ServableImage.java b/aos/atom_code/camera/java/aos/ServableImage.java
new file mode 100644
index 0000000..c5db252
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/ServableImage.java
@@ -0,0 +1,145 @@
+package aos;
+
+import java.util.ArrayDeque;
+import java.util.ArrayList;
+import java.util.Queue;
+import java.util.logging.Logger;
+
+import com.googlecode.javacv.cpp.opencv_core.IplImage;
+
+/**
+ * Provides {@link IplImage}s that can be used with a {@link DebugServer}.
+ */
+public class ServableImage {
+ @SuppressWarnings("unused")
+ private static final Logger LOG = Logger.getLogger(ServableImage.class
+ .getName());
+ private final int width, height, depth, channels;
+ private final ArrayList<Queue<IplImage>> queues = new ArrayList<Queue<IplImage>>();
+ private final ArrayList<IplImage> snapshots = new ArrayList<IplImage>();
+ private final IplImage current;
+ private int debugging = 0;
+
+ public ServableImage(int width, int height, int depth, int channels) {
+ this.width = width;
+ this.height = height;
+ this.depth = depth;
+ this.channels = channels;
+
+ current = IplImage.create(width, height, depth, channels);
+ }
+
+ /**
+ * @return the number of bytes in each image
+ */
+ public int imageSize() {
+ return width * height * depth * channels / 8;
+ }
+
+ /**
+ * @return the number of bits in each pixel
+ */
+ public short bitsPerPixel() {
+ return (short) (depth * channels);
+ }
+
+ /**
+ * Retrieves an image that should be used for debugging. It clears the value
+ * when called. {@link #releastSnapshot} MUST be called with the result.
+ *
+ * @param i
+ * Which snapshot to retrieve. 0 means the most recent final
+ * image.
+ * @return The most recent image at this index. {@code null} if there isn't
+ * a new one since last time this function was called. Will be in
+ * the correct color space to dump into a BMP image if this is a
+ * 3-channel image.
+ */
+ public synchronized IplImage getSnapshot(int i) {
+ if (snapshots.size() > i) {
+ return snapshots.get(i);
+ } else {
+ return null;
+ }
+ }
+
+ public synchronized void releaseSnapshot(int i, IplImage image) {
+ queues.get(i).add(image);
+ }
+
+ /**
+ * This function will return the same image if called repeatedly until
+ * {@link #releaseImage} is called.
+ *
+ * @return the current image
+ */
+ public synchronized IplImage getImage() {
+ return current;
+ }
+
+ /**
+ * Releases the current image (to be potentially sent out for debugging and
+ * then reused).
+ */
+ public synchronized void releaseImage() {
+ recordSnapshot(0);
+ }
+
+ /**
+ * Records a copy of the current image for debugging. It will be accessible
+ * at <{@code <base path>?i=<the value>}>. Does nothing unless
+ * {@link #isDebugging()}. This method <i>should</i> get called regardless
+ * of {@link #isDebugging()} to avoid outputting old debugging images. Note:
+ * 0 is not a valid snapshot number.
+ *
+ * @param i
+ * which snapshot this is
+ */
+ public synchronized void recordSnapshot(int i) {
+ while (queues.size() <= i) {
+ queues.add(null);
+ }
+ if (queues.get(i) == null) {
+ queues.set(i, new ArrayDeque<IplImage>());
+ }
+ while (snapshots.size() <= i) {
+ snapshots.add(null);
+ }
+ if (snapshots.get(i) != null) {
+ releaseSnapshot(i, snapshots.get(i));
+ }
+ if (isDebugging()) {
+ IplImage snapshot = queues.get(i).poll();
+ if (snapshot == null) {
+ snapshot = IplImage.create(width, height, depth, channels);
+ }
+ if (channels == 3) {
+ Natives.convertBGR2BMP(current.getByteBuffer(),
+ snapshot.getByteBuffer());
+ } else {
+ snapshot.getByteBuffer().put(current.getByteBuffer());
+ }
+ snapshots.set(i, snapshot);
+ } else {
+ snapshots.set(i, null);
+ }
+ }
+
+ /**
+ * @return whether or not to do extra debug work with the current image
+ */
+ public synchronized boolean isDebugging() {
+ return debugging > 0;
+ }
+
+ /**
+ * Whoever turns this on should turn it off when they're done.
+ */
+ synchronized void setDebugging(boolean debugging) {
+ if (debugging) {
+ ++this.debugging;
+ } else {
+ --this.debugging;
+ }
+ }
+}
diff --git a/aos/atom_code/camera/java/aos/Thresholder.java b/aos/atom_code/camera/java/aos/Thresholder.java
new file mode 100644
index 0000000..adf1b49
--- /dev/null
+++ b/aos/atom_code/camera/java/aos/Thresholder.java
@@ -0,0 +1,28 @@
+package aos;
+
+import com.googlecode.javacv.cpp.opencv_core;
+import com.googlecode.javacv.cpp.opencv_core.IplImage;
+
+public class Thresholder {
+ /**
+ * Thresholds in into out.
+ * All of the int arguments should be unsigned bytes except hoffset, which should be a signed byte.
+ * The min and max parameters specify what colors to accept.
+ * @param in The image to threshold. Must be a 3-channel {@link opencv_core#IPL_DEPTH_8U} image in the HSV color space.
+ * @param out Where to write the thresholded image to. Must be a 1-channel {@link opencv_core#IPL_DEPTH_8U} image.
+ * @param hoffset An offset to be added to the hue value before comparing it to {@code hmin} and {@code hmax}.
+ * The addition will be performed to a {@code uint8_t}, which will wrap around. This means that it must be positive.
+ * Useful for finding red values.
+ */
+ public static void threshold(IplImage in, IplImage out, int hoffset, int hmin, int hmax,
+ int smin, int smax, int vmin, int vmax) {
+ if (in.nChannels() != 3 || in.depth() != opencv_core.IPL_DEPTH_8U) {
+ throw new IllegalArgumentException("in is invalid");
+ }
+ if (out.nChannels() != 1 || out.depth() != opencv_core.IPL_DEPTH_8U) {
+ throw new IllegalArgumentException("out is invalid");
+ }
+ Natives.threshold(in.getByteBuffer(), out.getByteBuffer(), (short)hoffset,
+ (char)hmin, (char)hmax, (char)smin, (char)smax, (char)vmin, (char)vmax);
+ }
+}
diff --git a/aos/atom_code/camera/jni.cpp b/aos/atom_code/camera/jni.cpp
new file mode 100644
index 0000000..7b7eafa
--- /dev/null
+++ b/aos/atom_code/camera/jni.cpp
@@ -0,0 +1,257 @@
+#include <setjmp.h>
+
+#include "jni/aos_Natives.h"
+#include "aos/atom_code/camera/Buffers.h"
+#include "aos/externals/libjpeg/include/jpeglib.h"
+
+using aos::camera::Buffers;
+
+namespace {
+
+jclass nativeError, bufferError, outOfMemoryError;
+bool findClass(JNIEnv *env, const char *name, jclass *out) {
+ jclass local = env->FindClass(name);
+ if (out == NULL) return true;
+ *out = static_cast<jclass>(env->NewGlobalRef(local));
+ if (out == NULL) return true;
+ env->DeleteLocalRef(local);
+ return false;
+}
+
+// Checks that the size is correct and retrieves the address.
+// An expected_size of 0 means don't check it.
+// If this function returns NULL, a java exception will already have been
+// thrown.
+void *getBufferAddress(JNIEnv *env, jobject obj, jlong expected_size) {
+ if (obj == NULL) {
+ env->ThrowNew(nativeError, "null buffer");
+ return NULL;
+ }
+ if (expected_size != 0 &&
+ expected_size != env->GetDirectBufferCapacity(obj)) {
+ char *str;
+ if (asprintf(&str, "wrong size. expected %lld but got %lld",
+ expected_size, env->GetDirectBufferCapacity(obj)) < 0) {
+ env->ThrowNew(bufferError, "creating message failed");
+ return NULL;
+ }
+ env->ThrowNew(bufferError, str);
+ free(str);
+ return NULL;
+ }
+ void *const r = env->GetDirectBufferAddress(obj);
+ if (r == NULL) {
+ env->ThrowNew(bufferError, "couldn't get address");
+ }
+ return r;
+}
+
+const int kImagePixels = Buffers::kWidth * Buffers::kHeight;
+
+void jpeg_log_message(jpeg_common_struct *cinfo, log_level level) {
+ char buf[LOG_MESSAGE_LEN];
+ cinfo->err->format_message(cinfo, buf);
+ log_do(level, "libjpeg: %s\n", buf);
+}
+void jpeg_error_exit(jpeg_common_struct *cinfo) __attribute__((noreturn));
+void jpeg_error_exit(jpeg_common_struct *cinfo) {
+ jpeg_log_message(cinfo, ERROR);
+ longjmp(*static_cast<jmp_buf *>(cinfo->client_data), 1);
+}
+void jpeg_emit_message(jpeg_common_struct *cinfo, int msg_level) {
+ if (msg_level < 0) {
+ jpeg_log_message(cinfo, WARNING);
+ longjmp(*static_cast<jmp_buf *>(cinfo->client_data), 2);
+ }
+ // this spews a lot of messages out
+ //jpeg_log_message(cinfo, DEBUG);
+}
+
+// The structure used to hold all of the state for the functions that deal with
+// a Buffers. A pointer to this structure is stored java-side.
+struct BuffersHolder {
+ Buffers buffers;
+ timeval timestamp;
+ BuffersHolder() : buffers() {}
+};
+
+} // namespace
+
+void Java_aos_Natives_nativeInit(JNIEnv *env, jclass, jint width, jint height) {
+ if (findClass(env, "aos/NativeError", &nativeError)) return;
+ if (findClass(env, "aos/NativeBufferError", &bufferError)) return;
+ if (findClass(env, "java/lang/OutOfMemoryError", &outOfMemoryError)) return;
+
+ aos::InitNRT();
+
+ if (width != Buffers::kWidth || height != Buffers::kHeight) {
+ env->ThrowNew(nativeError, "dimensions mismatch");
+ return;
+ }
+
+ LOG(INFO, "nativeInit finished\n");
+}
+
+static_assert(sizeof(jlong) >= sizeof(void *),
+ "can't stick pointers into jlongs");
+
+jboolean Java_aos_Natives_decodeJPEG(JNIEnv *env, jclass, jlongArray stateArray,
+ jobject inobj, jint inLength,
+ jobject outobj) {
+ unsigned char *const in = static_cast<unsigned char *>(
+ getBufferAddress(env, inobj, 0));
+ if (in == NULL) return false;
+ if (env->GetDirectBufferCapacity(inobj) < inLength) {
+ env->ThrowNew(bufferError, "in is too small");
+ return false;
+ }
+ unsigned char *const out = static_cast<unsigned char *>(
+ getBufferAddress(env, outobj, kImagePixels * 3));
+ if (out == NULL) return false;
+
+ jpeg_decompress_struct *volatile cinfo; // volatile because of the setjmp call
+
+ jlong state;
+ env->GetLongArrayRegion(stateArray, 0, 1, &state);
+ if (env->ExceptionCheck()) return false;
+ if (state == 0) {
+ cinfo = static_cast<jpeg_decompress_struct *>(malloc(sizeof(*cinfo)));
+ if (cinfo == NULL) {
+ env->ThrowNew(outOfMemoryError, "malloc for jpeg_decompress_struct");
+ return false;
+ }
+ cinfo->err = jpeg_std_error(static_cast<jpeg_error_mgr *>(
+ malloc(sizeof(*cinfo->err))));
+ cinfo->client_data = malloc(sizeof(jmp_buf));
+ cinfo->err->error_exit = jpeg_error_exit;
+ cinfo->err->emit_message = jpeg_emit_message;
+ // if the error handler sees a failure, it needs to clean up
+ // (jpeg_abort_decompress) and then return the failure
+ // set cinfo->client_data to the jmp_buf
+ jpeg_create_decompress(cinfo);
+ state = reinterpret_cast<intptr_t>(cinfo);
+ env->SetLongArrayRegion(stateArray, 0, 1, &state);
+ if (env->ExceptionCheck()) return false;
+ } else {
+ cinfo = reinterpret_cast<jpeg_decompress_struct *>(state);
+ }
+
+ // set up the jump buffer
+ // this has to happen each time
+ if (setjmp(*static_cast<jmp_buf *>(cinfo->client_data))) {
+ jpeg_abort_decompress(cinfo);
+ return false;
+ }
+
+ jpeg_mem_src(cinfo, in, inLength);
+ jpeg_read_header(cinfo, TRUE);
+ if (cinfo->image_width != static_cast<unsigned int>(Buffers::kWidth) ||
+ cinfo->image_height != static_cast<unsigned int>(Buffers::kHeight)) {
+ LOG(WARNING, "got (%ux%u) image but expected (%dx%d)\n", cinfo->image_width,
+ cinfo->image_height, Buffers::kWidth, Buffers::kHeight);
+ jpeg_abort_decompress(cinfo);
+ return false;
+ }
+ cinfo->out_color_space = JCS_RGB;
+ jpeg_start_decompress(cinfo);
+ if (cinfo->output_components != 3) {
+ LOG(WARNING, "libjpeg wants to return %d color components instead of 3\n",
+ cinfo->out_color_components);
+ jpeg_abort_decompress(cinfo);
+ return false;
+ }
+ if (cinfo->output_width != static_cast<unsigned int>(Buffers::kWidth) ||
+ cinfo->output_height != static_cast<unsigned int>(Buffers::kHeight)) {
+ LOG(WARNING, "libjpeg wants to return a (%ux%u) image but need (%dx%d)\n",
+ cinfo->output_width, cinfo->output_height,
+ Buffers::kWidth, Buffers::kHeight);
+ jpeg_abort_decompress(cinfo);
+ return false;
+ }
+
+ unsigned char *buffers[Buffers::kHeight];
+ for (int i = 0; i < Buffers::kHeight; ++i) {
+ buffers[i] = &out[i * Buffers::kWidth * 3];
+ }
+ while (cinfo->output_scanline < cinfo->output_height) {
+ jpeg_read_scanlines(cinfo, &buffers[cinfo->output_scanline],
+ Buffers::kHeight - cinfo->output_scanline);
+ }
+
+ jpeg_finish_decompress(cinfo);
+ return true;
+}
+
+void Java_aos_Natives_threshold(JNIEnv *env, jclass, jobject inobj,
+ jobject outobj, jshort hoffset, jchar hmin,
+ jchar hmax, jchar smin, jchar smax, jchar vmin,
+ jchar vmax) {
+ const unsigned char *__restrict__ const in = static_cast<unsigned char *>(
+ getBufferAddress(env, inobj, kImagePixels * 3));
+ if (in == NULL) return;
+ char *__restrict__ const out = static_cast<char *>(
+ getBufferAddress(env, outobj, kImagePixels));
+ if (out == NULL) return;
+
+ for (int i = 0; i < kImagePixels; ++i) {
+ const uint8_t h = in[i * 3] + static_cast<uint8_t>(hoffset);
+ out[i] = h > hmin && h < hmax &&
+ in[i * 3 + 1] > smin && in[i * 3 + 1] < smax &&
+ in[i * 3 + 2] > vmin && in[i * 3 + 2] < vmax;
+ }
+}
+void Java_aos_Natives_convertBGR2BMP(JNIEnv *env, jclass,
+ jobject inobj, jobject outobj) {
+ const char *__restrict__ const in = static_cast<char *>(
+ getBufferAddress(env, inobj, kImagePixels * 3));
+ if (in == NULL) return;
+ char *__restrict__ const out = static_cast<char *>(
+ getBufferAddress(env, outobj, kImagePixels * 3));
+ if (out == NULL) return;
+
+ for (int i = 0; i < kImagePixels; ++i) {
+ out[i * 3 + 0] = in[i * 3 + 2];
+ out[i * 3 + 1] = in[i * 3 + 1];
+ out[i * 3 + 2] = in[i * 3 + 0];
+ }
+}
+
+jlong Java_aos_Natives_queueInit(JNIEnv *, jclass) {
+ return reinterpret_cast<intptr_t>(new BuffersHolder());
+}
+void Java_aos_Natives_queueReleaseJPEG(JNIEnv *, jclass, jlong ptr) {
+ reinterpret_cast<BuffersHolder *>(ptr)->buffers.Release();
+}
+jobject Java_aos_Natives_queueGetJPEG(JNIEnv *env, jclass, jlong ptr) {
+ uint32_t size;
+ BuffersHolder *const holder = reinterpret_cast<BuffersHolder *>(ptr);
+ const void *const r = holder->buffers.GetNext(true, &size,
+ &holder->timestamp, NULL);
+ if (r == NULL) return NULL;
+ return env->NewDirectByteBuffer(const_cast<void *>(r), size);
+}
+jdouble Java_aos_Natives_queueGetTimestamp(JNIEnv *, jclass, jlong ptr) {
+ const BuffersHolder *const holder = reinterpret_cast<BuffersHolder *>(ptr);
+ return holder->timestamp.tv_sec + holder->timestamp.tv_usec / 1000000.0;
+}
+
+void Java_aos_Natives_LOG(JNIEnv *env, jclass, jstring message, jint jlevel) {
+ log_level level;
+ if (jlevel >= 1000) {
+ // Don't want to use FATAL because the uncaught java exception that is
+ // likely to come next will be useful.
+ level = ERROR;
+ } else if (jlevel >= 900) {
+ level = WARNING;
+ } else if (jlevel >= 800) {
+ level = INFO;
+ } else {
+ level = DEBUG;
+ }
+ // can't use Get/ReleaseStringCritical because log_do might block waiting to
+ // put its message into the queue
+ const char *const message_chars = env->GetStringUTFChars(message, NULL);
+ if (message_chars == NULL) return;
+ log_do(level, "%s\n", message_chars);
+ env->ReleaseStringUTFChars(message, message_chars);
+}
diff --git a/aos/atom_code/core/BinaryLogReader.cpp b/aos/atom_code/core/BinaryLogReader.cpp
new file mode 100644
index 0000000..703a219
--- /dev/null
+++ b/aos/atom_code/core/BinaryLogReader.cpp
@@ -0,0 +1,123 @@
+#include <stdio.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <time.h>
+#include <string.h>
+#include <string>
+#include <unistd.h>
+#include <sys/types.h>
+#include <pwd.h>
+#include <fcntl.h>
+
+#include <map>
+
+#include "aos/aos_core.h"
+#include "aos/atom_code/core/LogFileCommon.h"
+
+static const char *const kCRIOName = "CRIO";
+
+int main() {
+ aos::InitNRT();
+
+ char *folder_tmp;
+ if (asprintf(&folder_tmp, "%s/tmp/robot_logs", getpwuid(getuid())->pw_dir) == -1) {
+ LOG(ERROR, "couldn't figure out what folder to use because of %d (%s)\n",
+ errno, strerror(errno));
+ return EXIT_FAILURE;
+ }
+ std::string hack("/home/driver/tmp/robot_logs"); // TODO(brians) remove this hack
+ const char *folder = hack.c_str();
+ if (access(folder, R_OK | W_OK) == -1) {
+ fprintf(stderr,
+ "LogReader: error: folder '%s' does not exist. please create it\n",
+ folder);
+ return EXIT_FAILURE;
+ }
+ LOG(INFO, "logging to folder '%s'\n", folder);
+
+ const time_t t = time(NULL);
+ char *tmp;
+ if (asprintf(&tmp, "%s/aos_log-%jd", folder, static_cast<uintmax_t>(t)) == -1) {
+ fprintf(stderr, "BinaryLogReader: couldn't create final name because of %d (%s)."
+ " exiting\n", errno, strerror(errno));
+ return EXIT_FAILURE;
+ }
+ char *tmp2;
+ if (asprintf(&tmp2, "%s/aos_log-current", folder) == -1) {
+ fprintf(stderr, "BinaryLogReader: couldn't create symlink name because of %d (%s)."
+ " not creating current symlink\n", errno, strerror(errno));
+ } else {
+ if (unlink(tmp2) == -1 && (errno != EROFS && errno != ENOENT)) {
+ fprintf(stderr, "BinaryLogReader: warning: unlink('%s') failed because of %d (%s)\n",
+ tmp2, errno, strerror(errno));
+ }
+ if (symlink(tmp, tmp2) == -1) {
+ fprintf(stderr, "BinaryLogReader: warning: symlink('%s', '%s') failed"
+ " because of %d (%s)\n", tmp, tmp2, errno, strerror(errno));
+ }
+ free(tmp2);
+ }
+ int fd = open(tmp, O_SYNC | O_APPEND | O_RDWR | O_CREAT,
+ S_IRUSR | S_IWUSR | S_IRGRP | S_IWGRP | S_IROTH | S_IWOTH);
+ free(tmp);
+ if (fd == -1) {
+ fprintf(stderr, "BinaryLogReader: couldn't open file '%s' because of %d (%s)."
+ " exiting\n", tmp, errno, strerror(errno));
+ return EXIT_FAILURE;
+ }
+ aos::LogFileAccessor writer(fd, true);
+
+ struct timespec timespec;
+ time_t last_sec = 0;
+ while (true) {
+ clock_gettime(CLOCK_MONOTONIC, ×pec);
+ if (last_sec != timespec.tv_sec) {
+ LOG(INFO, "msyncing output\n");
+ last_sec = timespec.tv_sec;
+ writer.Sync();
+ }
+
+ const log_message *const msg = log_read_next();
+ if (msg == NULL) continue;
+ const log_crio_message *const crio_msg = reinterpret_cast<const log_crio_message *>(
+ msg);
+
+ size_t name_size, message_size;
+ if (msg->source == -1) {
+ name_size = strlen(kCRIOName);
+ message_size = strlen(crio_msg->message);
+ } else {
+ name_size = strlen(msg->name);
+ message_size = strlen(msg->message);
+ }
+ // add on size for terminating '\0'
+ name_size += 1;
+ message_size += 1;
+
+ aos::LogFileMessageHeader *const output = writer.GetWritePosition(
+ sizeof(aos::LogFileMessageHeader) + name_size + message_size);
+ char *output_strings = reinterpret_cast<char *>(output) + sizeof(*output);
+ output->name_size = name_size;
+ output->message_size = message_size;
+ output->source = msg->source;
+ if (msg->source == -1) {
+ output->level = crio_msg->level;
+ // TODO(brians) figure out what time to put in
+ output->sequence = crio_msg->sequence;
+ memcpy(output_strings, kCRIOName, name_size);
+ memcpy(output_strings + name_size, crio_msg->message, message_size);
+ } else {
+ output->level = msg->level;
+ output->time_sec = msg->time.tv_sec;
+ output->time_nsec = msg->time.tv_nsec;
+ output->sequence = msg->sequence;
+ memcpy(output_strings, msg->name, name_size);
+ memcpy(output_strings + name_size, msg->message, message_size);
+ }
+ condition_set(&output->marker);
+
+ log_free_message(msg);
+ }
+
+ aos::Cleanup();
+}
diff --git a/aos/atom_code/core/CRIOLogReader.cpp b/aos/atom_code/core/CRIOLogReader.cpp
new file mode 100644
index 0000000..f32e21d
--- /dev/null
+++ b/aos/atom_code/core/CRIOLogReader.cpp
@@ -0,0 +1,129 @@
+#include <sys/socket.h>
+#include <netinet/in.h>
+#include <netinet/tcp.h>
+#include <sys/select.h>
+#include <sys/types.h>
+#include <unistd.h>
+#include <sys/time.h>
+#include <fcntl.h>
+#include <arpa/inet.h>
+#include <errno.h>
+
+#include <map>
+
+#include "aos/aos_core.h"
+#include "aos/common/Configuration.h"
+#include "aos/common/byteorder.h"
+
+struct log_buffer {
+ log_crio_message msg;
+ size_t used;
+
+ log_buffer() {
+ Clear();
+ }
+ void Clear() {
+ used = 0;
+ }
+ // returns whether msg is now complete
+ bool ReceiveFrom(int sock) {
+ const ssize_t ret = recv(sock, reinterpret_cast<uint8_t *>(&msg) + used,
+ sizeof(msg) - used, 0);
+ if (ret == -1) {
+ LOG(ERROR, "recv(%d, %p, %d) failed because of %d: %s\n",
+ sock, reinterpret_cast<uint8_t *>(&msg) + used, sizeof(msg) - used,
+ errno, strerror(errno));
+ return false;
+ } else {
+ used += ret;
+ if (used > sizeof(msg)) {
+ LOG(WARNING, "used(%zd) is > sizeof(msg)(%zd)\n", used, sizeof(msg));
+ }
+ return used >= sizeof(msg);
+ }
+ }
+};
+
+int main() {
+ aos::InitNRT();
+
+ const int sock = socket(AF_INET, SOCK_STREAM, 0);
+ if (sock == -1) {
+ LOG(ERROR, "creating TCP socket failed because of %d: %s\n",
+ errno, strerror(errno));
+ return EXIT_FAILURE;
+ }
+ union {
+ sockaddr_in in;
+ sockaddr addr;
+ } bind_sockaddr;
+ memset(&bind_sockaddr, 0, sizeof(bind_sockaddr));
+ bind_sockaddr.in.sin_family = AF_INET;
+ bind_sockaddr.in.sin_port = htons(static_cast<uint16_t>(aos::NetworkPort::kLogs));
+ bind_sockaddr.in.sin_addr.s_addr = htonl(INADDR_ANY);
+ if (bind(sock, &bind_sockaddr.addr, sizeof(bind_sockaddr.addr)) == -1) {
+ LOG(ERROR, "bind(%d, %p) failed because of %d: %s\n", sock, &bind_sockaddr.addr,
+ errno, strerror(errno));
+ return EXIT_FAILURE;
+ }
+ if (listen(sock, 10) == -1) {
+ LOG(ERROR, "listen(%d) failed because of %d: %s\n", sock,
+ errno, strerror(errno));
+ return EXIT_FAILURE;
+ }
+ const int flags = fcntl(sock, F_GETFL, 0);
+ if (flags == -1) {
+ LOG(ERROR, "fcntl(%d, F_GETFL, 0) failed because of %d: %s\n", sock,
+ errno, strerror(errno));
+ return EXIT_FAILURE;
+ }
+ if (fcntl(sock, F_SETFL, flags | O_NONBLOCK) == -1) {
+ LOG(ERROR, "fcntl(%d, F_SETFL, %x) failed because of %d: %s\n",
+ sock, flags | O_NONBLOCK, errno, strerror(errno));
+ return EXIT_FAILURE;
+ }
+
+ std::map<int, log_buffer> socks;
+ fd_set read_fds;
+ while (true) {
+ FD_ZERO(&read_fds);
+ FD_SET(sock, &read_fds);
+ for (auto it = socks.begin(); it != socks.end(); ++it) {
+ FD_SET(it->first, &read_fds);
+ }
+ switch (select(FD_SETSIZE, &read_fds, NULL /*write*/, NULL /*err*/,
+ NULL /*timeout*/)) {
+ case -1:
+ LOG(ERROR, "select(FD_SETSIZE, %p, NULL, NULL, NULL) failed "
+ "because of %d: %s\n", &read_fds, errno, strerror(errno));
+ continue;
+ case 0:
+ LOG(ERROR, "select with NULL timeout timed out...\n");
+ continue;
+ }
+
+ if (FD_ISSET(sock, &read_fds)) {
+ const int new_sock = accept4(sock, NULL, NULL, SOCK_NONBLOCK);
+ if (new_sock == -1) {
+ LOG(ERROR, "accept4(%d, NULL, NULL, SOCK_NONBLOCK(=%d)) failed "
+ "because of %d: %s\n",
+ sock, SOCK_NONBLOCK, errno, strerror(errno));
+ } else {
+ socks[new_sock]; // creates using value's default constructor
+ }
+ }
+
+ for (auto it = socks.begin(); it != socks.end(); ++it) {
+ if (FD_ISSET(it->first, &read_fds)) {
+ if (it->second.ReceiveFrom(it->first)) {
+ it->second.msg.identifier = -1;
+ it->second.msg.time = aos::ntoh(it->second.msg.time);
+ log_crio_message_send(it->second.msg);
+ it->second.Clear();
+ }
+ }
+ }
+ }
+
+ aos::Cleanup();
+}
diff --git a/aos/atom_code/core/LogDisplayer.cpp b/aos/atom_code/core/LogDisplayer.cpp
new file mode 100644
index 0000000..9dee08f
--- /dev/null
+++ b/aos/atom_code/core/LogDisplayer.cpp
@@ -0,0 +1,157 @@
+#include <stdio.h>
+#include <stdlib.h>
+#include <getopt.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <fcntl.h>
+#include <inttypes.h>
+#include <errno.h>
+
+#include "aos/atom_code/core/LogFileCommon.h"
+#include "aos/aos_core.h"
+
+namespace {
+
+const char *kArgsHelp = "[OPTION]... [FILE]\n"
+ "Display log file FILE (created by BinaryLogReader) to stdout.\n"
+ "FILE is \"aos_log-current\" by default.\n"
+ "\n"
+ " -n, --name NAME only display entries from processes named NAME\n"
+ " -l, --level LEVEL "
+ "only display log entries at least as important as LEVEL\n"
+ " // -p, --pid PID only display log entries from process PID\n"
+ " -f, --follow "
+ "wait when the end of the file is reached (implies --end)\n"
+ " -t, --terminate stop when the end of file is reached (default)\n"
+ " -b, --beginning start at the beginning of the file (default)\n"
+ " -e, --end start at the end of the file\n"
+ " -s, --skip NUMBER skip NUMBER matching logs\n"
+ " // -m, --max NUMBER only display up to NUMBER logs\n"
+ " // -o, --format FORMAT use FORMAT to display log entries\n"
+ "\n"
+ "LEVEL must be DEBUG, INFO, WARNING, ERROR, or FATAL.\n"
+ " It defaults to INFO.\n"
+ "\n"
+ "TODO(brians) implement the commented out ones and changing FILE\n";
+
+void PrintHelpAndExit() {
+ fprintf(stderr, "Usage: %s %s", program_invocation_name, kArgsHelp);
+
+ exit(EXIT_SUCCESS);
+}
+
+} // namespace
+
+int main(int argc, char **argv) {
+ const char *filter_name = NULL;
+ log_level filter_level = INFO;
+ bool follow = false, start_at_beginning = true;
+ const char *filename = "aos_log-current";
+
+ while (true) {
+ static struct option long_options[] = {
+ {"name", required_argument, NULL, 'n'},
+ {"level", required_argument, NULL, 'l'},
+ {"pid", required_argument, NULL, 'p'},
+
+ {"follow", no_argument, NULL, 'f'},
+ {"terminate", no_argument, NULL, 't'},
+ {"beginning", no_argument, NULL, 'b'},
+ {"end", no_argument, NULL, 'e'},
+ {"skip", required_argument, NULL, 's'},
+ {"max", required_argument, NULL, 'm'},
+
+ {"format", required_argument, NULL, 'o'},
+
+ {"help", no_argument, NULL, 'h'},
+ {0, 0, 0, 0}
+ };
+ int option_index = 0;
+
+ const int c = getopt_long(argc, argv, "n:l:p:fts:m:o:h",
+ long_options, &option_index);
+ if (c == -1) { // if we're at the end
+ break;
+ }
+ switch (c) {
+ case 0:
+ fprintf(stderr, "LogDisplayer: got a 0 option but didn't set up any\n");
+ abort();
+ case 'n':
+ filter_name = optarg;
+ break;
+ case 'l':
+ filter_level = str_log(optarg);
+ if (filter_level == LOG_UNKNOWN) {
+ fprintf(stderr, "LogDisplayer: unknown log level '%s'\n", optarg);
+ exit(EXIT_FAILURE);
+ }
+ break;
+ case 'p':
+ abort();
+ break;
+ case 'f':
+ follow = true;
+ start_at_beginning = false;
+ break;
+ case 't':
+ follow = false;
+ break;
+ case 'b':
+ start_at_beginning = true;
+ break;
+ case 'e':
+ start_at_beginning = false;
+ break;
+ case 'm':
+ abort();
+ break;
+ case 'o':
+ abort();
+ break;
+ case 'h':
+ PrintHelpAndExit();
+ break;
+ case '?':
+ break;
+ default:
+ fprintf(stderr, "LogDisplayer: in a bad spot (%s: %d)\n", __FILE__, __LINE__);
+ abort();
+ }
+ }
+
+ fprintf(stderr, "displaying down to level %s from file '%s'\n",
+ log_str(filter_level), filename);
+ if (optind < argc) {
+ fprintf(stderr, "non-option ARGV-elements: ");
+ while (optind < argc) {
+ fprintf(stderr, "%s\n", argv[optind++]);
+ }
+ }
+
+ int fd = open(filename, O_RDONLY);
+ if (fd == -1) {
+ fprintf(stderr, "error: couldn't open file '%s' for reading because of %s\n",
+ filename, strerror(errno));
+ exit(EXIT_FAILURE);
+ }
+ aos::LogFileAccessor accessor(fd, false);
+ if (!start_at_beginning) {
+ accessor.MoveToEnd();
+ }
+ const aos::LogFileMessageHeader *msg;
+ do {
+ msg = accessor.ReadNextMessage(follow);
+ if (msg == NULL) continue;
+ if (log_gt_important(filter_level, msg->level)) continue;
+ if (filter_name != NULL &&
+ strcmp(filter_name, reinterpret_cast<const char *>(msg) + sizeof(*msg)) != 0) {
+ continue;
+ }
+ printf("%s(%"PRId32")(%03"PRId8"): %s at %010"PRIu64"s%09"PRIu64"ns: %s",
+ reinterpret_cast<const char *>(msg) + sizeof(*msg), msg->source,
+ msg->sequence, log_str(msg->level), msg->time_sec, msg->time_nsec,
+ reinterpret_cast<const char *>(msg) + sizeof(*msg) + msg->name_size);
+ } while (msg != NULL);
+}
+
diff --git a/aos/atom_code/core/LogFileCommon.h b/aos/atom_code/core/LogFileCommon.h
new file mode 100644
index 0000000..235c55b
--- /dev/null
+++ b/aos/atom_code/core/LogFileCommon.h
@@ -0,0 +1,192 @@
+#ifndef AOS_ATOM_CODE_CORE_LOG_FILE_COMMON_H_
+#define AOS_ATOM_CODE_CORE_LOG_FILE_COMMON_H_
+
+#include <stdio.h>
+#include <errno.h>
+#include <string.h>
+#include <sys/mman.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <unistd.h>
+
+#include <algorithm>
+
+#include "aos/aos_core.h"
+
+namespace aos {
+
+// File format: {
+// LogFileMessageHeader header;
+// char *name; // of the process that wrote the message
+// char *message;
+// } not crossing kPageSize boundaries into the file.
+//
+// Field sizes designed to fit the various values from log_message even on
+// other machines (hopefully) because they're baked into the files.
+struct __attribute__((aligned)) LogFileMessageHeader {
+ // gets condition_set once this one has been written
+ // for readers keeping up with a live writer
+ //
+ // gets initialized to 0 by ftruncate
+ //
+ // there will be something here after the last log on a "page" set to 2
+ // (by the condition_set) to indicate that the next log is on the next page
+ mutex marker;
+ static_assert(sizeof(marker) == 4, "mutex changed size!");
+ log_level level;
+ static_assert(sizeof(level) == 1, "log_level changed size!");
+
+ uint64_t time_sec;
+ static_assert(sizeof(time_sec) >= sizeof(log_message::time.tv_sec), "tv_sec won't fit");
+ uint64_t time_nsec;
+ static_assert(sizeof(time_nsec) >= sizeof(log_message::time.tv_nsec),
+ "tv_nsec won't fit");
+
+ int32_t source; // pid or -1 for crio
+ static_assert(sizeof(source) >= sizeof(log_message::source), "PIDs won't fit");
+ uint8_t sequence;
+ static_assert(sizeof(sequence) == sizeof(log_crio_message::sequence),
+ "something changed");
+ static_assert(sizeof(sequence) == sizeof(log_message::sequence),
+ "something changed");
+
+ // both including the terminating '\0'
+ uint32_t name_size;
+ uint32_t message_size;
+};
+static_assert(std::is_pod<LogFileMessageHeader>::value,
+ "LogFileMessageHeader will to get dumped to a file");
+
+// Handles the mmapping and munmapping for reading and writing log files.
+class LogFileAccessor {
+ private:
+ // The size of the chunks that get mmaped/munmapped together. Large enough so
+ // that not too much space is wasted and it's hopefully bigger than and a
+ // multiple of the system page size but small enough so that really large chunks
+ // of memory don't have to get mapped at the same time.
+ static const size_t kPageSize = 32768;
+ // What to align messages to. Necessary for futexes to work.
+ static const size_t kAlignment = 64;
+ static_assert(kAlignment >= __alignof__(mutex), "futexes will complain");
+
+ const int fd_;
+ const bool writable_;
+
+ off_t offset_; // into the file. will be aligned to kPageSize
+ char *current_;
+ size_t position_;
+
+ inline unsigned long SystemPageSize() {
+ static unsigned long r = sysconf(_SC_PAGESIZE);
+ return r;
+ }
+ void MapNextPage() {
+ if (writable_) {
+ if (ftruncate(fd_, offset_ + kPageSize) == -1) {
+ fprintf(stderr, "ftruncate(%d, %zd) failed with %d: %s. aborting\n",
+ fd_, kPageSize, errno, strerror(errno));
+ printf("see stderr\n");
+ abort();
+ }
+ }
+ current_ = static_cast<char *>(mmap(NULL, kPageSize,
+ PROT_READ | (writable_ ? PROT_WRITE : 0),
+ MAP_SHARED, fd_, offset_));
+ if (current_ == MAP_FAILED) {
+ fprintf(stderr, "mmap(NULL, %zd, PROT_READ | PROT_WRITE, MAP_SHARED, %d, %jd)"
+ " failed with %d: %s. aborting\n", kPageSize, fd_,
+ static_cast<intmax_t>(offset_), errno, strerror(errno));
+ printf("see stderr\n");
+ abort();
+ }
+ offset_ += kPageSize;
+ }
+ void Unmap(void *location) {
+ if (munmap(location, kPageSize) == -1) {
+ fprintf(stderr, "munmap(%p, %zd) failed with %d: %s. aborting\n",
+ location, kPageSize, errno, strerror(errno));
+ printf("see stderr\n");
+ abort();
+ }
+ }
+ public:
+ LogFileAccessor(int fd, bool writable) : fd_(fd), writable_(writable),
+ offset_(0), current_(0), position_(0) {
+ // check to make sure that mmap will allow mmaping in chunks of kPageSize
+ if (SystemPageSize() > kPageSize || (kPageSize % SystemPageSize()) != 0) {
+ fprintf(stderr, "LogFileCommon: system page size (%lu)"
+ " not compatible with kPageSize (%zd). aborting\n",
+ SystemPageSize(), kPageSize);
+ printf("see stderr\n");
+ abort();
+ }
+
+ MapNextPage();
+ }
+ // message_size should be the total number of bytes needed for the message
+ LogFileMessageHeader *GetWritePosition(size_t message_size) {
+ if (position_ + message_size + (kAlignment - (message_size % kAlignment)) +
+ sizeof(mutex) > kPageSize) {
+ char *const temp = current_;
+ MapNextPage();
+ if (condition_set_value(reinterpret_cast<mutex *>(&temp[position_]), 2) != 0) {
+ fprintf(stderr, "LogFileCommon: condition_set_value(%p, 2) failed with %d: %s."
+ " readers will hang\n", &temp[position_], errno, strerror(errno));
+ }
+ Unmap(temp);
+ position_ = 0;
+ }
+ LogFileMessageHeader *const r = reinterpret_cast<LogFileMessageHeader *>(
+ ¤t_[position_]);
+ position_ += message_size;
+ // keep it aligned for next time
+ position_ += kAlignment - (position_ % kAlignment);
+ return r;
+ }
+ // may only return NULL if wait is false
+ const LogFileMessageHeader *ReadNextMessage(bool wait) {
+ LogFileMessageHeader *r;
+ do {
+ r = reinterpret_cast<LogFileMessageHeader *>(¤t_[position_]);
+ if (wait) {
+ if (condition_wait(&r->marker) != 0) continue;
+ }
+ if (r->marker == 2) {
+ Unmap(current_);
+ MapNextPage();
+ position_ = 0;
+ r = reinterpret_cast<LogFileMessageHeader *>(current_);
+ }
+ } while (wait && r->marker == 0);
+ if (r->marker == 0) {
+ return NULL;
+ }
+ position_ += sizeof(LogFileMessageHeader) + r->name_size + r->message_size;
+ // keep it aligned for next time
+ position_ += kAlignment - (position_ % kAlignment);
+ return r;
+ }
+
+ // asynchronously syncs all open mappings
+ void Sync() {
+ msync(current_, kPageSize, MS_ASYNC | MS_INVALIDATE);
+ }
+
+ void MoveToEnd() {
+ Unmap(current_);
+ struct stat info;
+ if (fstat(fd_, &info) == -1) {
+ fprintf(stderr, "LOgFileCommon: fstat(%d, %p) failed with %d: %s\n",
+ fd_, &info, errno, strerror(errno));
+ printf("see stderr\n");
+ abort();
+ }
+ offset_ = info.st_size - kPageSize;
+ MapNextPage();
+ }
+};
+
+};
+
+#endif
+
diff --git a/aos/atom_code/core/LogStreamer.cpp b/aos/atom_code/core/LogStreamer.cpp
new file mode 100644
index 0000000..ceec18d
--- /dev/null
+++ b/aos/atom_code/core/LogStreamer.cpp
@@ -0,0 +1,44 @@
+#include <stdio.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <time.h>
+#include <string.h>
+#include <string>
+#include <unistd.h>
+#include <sys/types.h>
+#include <pwd.h>
+#include <fcntl.h>
+#include <inttypes.h>
+
+#include "aos/aos_core.h"
+#include "aos/atom_code/core/LogFileCommon.h"
+
+static const char *const kCRIOName = "CRIO";
+
+int main() {
+ aos::InitNRT();
+
+ const time_t t = time(NULL);
+ printf("starting at %jd----------------------------------\n", static_cast<uintmax_t>(t));
+
+ int index = 0;
+ while (true) {
+ const log_message *const msg = log_read_next2(BLOCK, &index);
+ if (msg == NULL) continue;
+ const log_crio_message *const crio_msg = reinterpret_cast<const log_crio_message *>(
+ msg);
+
+ if (msg->source == -1) {
+ printf("CRIO(%03"PRId8"): %s at %f: %s", crio_msg->sequence,
+ log_str(crio_msg->level), crio_msg->time, crio_msg->message);
+ } else {
+ printf("%s(%"PRId32")(%03"PRId8"): %s at %010jus%09luns: %s",
+ msg->name, msg->source, msg->sequence, log_str(msg->level),
+ static_cast<uintmax_t>(msg->time.tv_sec), msg->time.tv_nsec, msg->message);
+ }
+
+ log_free_message(msg);
+ }
+
+ aos::Cleanup();
+}
diff --git a/aos/atom_code/core/core.cc b/aos/atom_code/core/core.cc
new file mode 100644
index 0000000..b34169b
--- /dev/null
+++ b/aos/atom_code/core/core.cc
@@ -0,0 +1,15 @@
+// This is the core scheduling system
+//
+// Purposes: All shared memory gets allocated here.
+//
+
+#include <stdio.h>
+#include <string.h>
+#include <unistd.h>
+#include "aos/aos_core.h"
+
+int main() {
+ aos::InitCreate();
+ select(0, NULL, NULL, NULL, NULL); // wait forever
+ aos::Cleanup();
+}
diff --git a/aos/atom_code/core/core.gyp b/aos/atom_code/core/core.gyp
new file mode 100644
index 0000000..04d3cc8
--- /dev/null
+++ b/aos/atom_code/core/core.gyp
@@ -0,0 +1,54 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'core',
+ 'type': 'executable',
+ 'sources': [
+ 'core.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ {
+ 'target_name': 'BinaryLogReader',
+ 'type': 'executable',
+ 'sources': [
+ 'BinaryLogReader.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ {
+ 'target_name': 'LogStreamer',
+ 'type': 'executable',
+ 'sources': [
+ 'LogStreamer.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ {
+ 'target_name': 'LogDisplayer',
+ 'type': 'executable',
+ 'sources': [
+ 'LogDisplayer.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ {
+ 'target_name': 'CRIOLogReader',
+ 'type': 'executable',
+ 'sources': [
+ 'CRIOLogReader.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ ],
+}
diff --git a/aos/atom_code/init.cc b/aos/atom_code/init.cc
new file mode 100644
index 0000000..4776261
--- /dev/null
+++ b/aos/atom_code/init.cc
@@ -0,0 +1,115 @@
+#include "aos/atom_code/init.h"
+
+#include <stdio.h>
+#include <string.h>
+#include <sys/mman.h>
+#include <errno.h>
+#include <sched.h>
+#include <sys/resource.h>
+#include <asm-generic/resource.h> // for RLIMIT_RTTIME
+#include <sys/types.h>
+#include <unistd.h>
+#include <stdlib.h>
+#include <stdint.h>
+
+#include "aos/aos_core.h"
+#include "aos/common/die.h"
+
+namespace aos {
+
+namespace {
+
+void SetSoftRLimit(int resource, rlim64_t soft) {
+ // If we're root, then we don't need to change the soft limits because none of
+ // the ones we care about get checked for root.
+ if (getuid() != 0) {
+ struct rlimit64 rlim;
+ if (getrlimit64(resource, &rlim) == -1) {
+ Die("%s-init: getrlimit64(%d) failed with %d (%s)\n",
+ program_invocation_short_name, resource, errno, strerror(errno));
+ }
+ rlim.rlim_cur = soft;
+ if (setrlimit64(resource, &rlim) == -1) {
+ Die("%s-init: setrlimit64(%d, {cur=%jd,max=%jd})"
+ " failed with %d (%s)\n", program_invocation_short_name,
+ resource, (intmax_t)rlim.rlim_cur, (intmax_t)rlim.rlim_max,
+ errno, strerror(errno));
+ }
+ }
+}
+
+// Common stuff that needs to happen at the beginning of both the realtime and
+// non-realtime initialization sequences. May be called twice.
+void InitStart() {
+ // Allow locking as much as we want into RAM.
+ SetSoftRLimit(RLIMIT_MEMLOCK, RLIM_INFINITY);
+}
+
+int LockAllMemory() {
+ InitStart();
+ if (mlockall(MCL_CURRENT | MCL_FUTURE) == -1) {
+ Die("%s-init: mlockall failed with %d (%s)\n",
+ program_invocation_short_name, errno, strerror(errno));
+ }
+
+ // Forces the memory pages for all the stack space that we're ever going to
+ // use to be loaded into memory (so it can be locked there).
+ uint8_t data[4096 * 8];
+ // Not 0 because linux might optimize that to a 0-filled page.
+ memset(data, 1, sizeof(data));
+
+ return 0;
+}
+
+// Do the initialization code that is necessary for both realtime and
+// non-realtime processes.
+void DoInitNRT(aos_core_create create) {
+ InitStart();
+ if (aos_core_create_shared_mem(create)) {
+ Die("%s-init: creating shared memory reference failed\n",
+ program_invocation_short_name);
+ }
+ if (log_init(program_invocation_short_name) != 0) {
+ Die("%s-init: initializing logging failed\n",
+ program_invocation_short_name);
+ }
+}
+
+const char *const kNoRealtimeEnvironmentVariable = "AOS_NO_REALTIME";
+
+} // namespace
+
+void InitNRT() { DoInitNRT(aos_core_create::reference); }
+void InitCreate() { DoInitNRT(aos_core_create::create); }
+void Init() {
+ if (getenv(kNoRealtimeEnvironmentVariable) == NULL) { // if nobody set it
+ LockAllMemory();
+ // Only let rt processes run for 1 second straight.
+ SetSoftRLimit(RLIMIT_RTTIME, 1000000);
+ // Allow rt processes up to priority 40.
+ SetSoftRLimit(RLIMIT_RTPRIO, 40);
+ // Set our process to priority 40.
+ struct sched_param param;
+ param.sched_priority = 40;
+ if (sched_setscheduler(0, SCHED_FIFO, ¶m) != 0) {
+ Die("%s-init: setting SCHED_FIFO failed with %d (%s)\n",
+ program_invocation_short_name, errno, strerror(errno));
+ }
+ } else {
+ fprintf(stderr, "%s not doing realtime initialization because environment"
+ " variable %s is set\n", program_invocation_short_name,
+ kNoRealtimeEnvironmentVariable);
+ printf("no realtime for %s. see stderr\n", program_invocation_short_name);
+ }
+
+ InitNRT();
+}
+
+void Cleanup() {
+ if (aos_core_free_shared_mem()) {
+ Die("%s-init: freeing shared mem failed\n",
+ program_invocation_short_name);
+ }
+}
+
+} // namespace aos
diff --git a/aos/atom_code/init.h b/aos/atom_code/init.h
new file mode 100644
index 0000000..ffb7afc
--- /dev/null
+++ b/aos/atom_code/init.h
@@ -0,0 +1,19 @@
+#ifndef AOS_ATOM_CODE_INIT_H_
+#define AOS_ATOM_CODE_INIT_H_
+
+namespace aos {
+
+// Does the non-realtime parts of the initialization process.
+void InitNRT();
+// Initializes everything, including the realtime stuff.
+void Init();
+// Same as InitNRT, except will remove an existing shared memory file and create
+// a new one.
+void InitCreate();
+// Cleans up (probably not going to get called very often because few things can
+// exit gracefully).
+void Cleanup();
+
+} // namespace aos
+
+#endif // AOS_ATOM_CODE_INIT_H_
diff --git a/aos/atom_code/input/FRCComm.h b/aos/atom_code/input/FRCComm.h
new file mode 100644
index 0000000..3d2f4c0
--- /dev/null
+++ b/aos/atom_code/input/FRCComm.h
@@ -0,0 +1,115 @@
+/*************************************************************
+ * NOTICE
+ *
+ * These are the only externally exposed functions to the
+ * NetworkCommunication library
+ *
+ * This is an implementation of FRC Spec for Comm Protocol
+ * Revision 4.5, June 30, 2008
+ *
+ * Copyright (c) National Instruments 2008. All Rights Reserved.
+ *
+ *************************************************************/
+
+#ifndef __FRC_COMM_H__
+#define __FRC_COMM_H__
+
+#include <stdint.h>
+
+typedef uint64_t UINT64;
+typedef uint32_t UINT32;
+typedef uint16_t UINT16;
+typedef uint8_t UINT8;
+typedef int8_t INT8;
+
+struct FRCCommonControlData{
+ UINT16 packetIndex;
+ union {
+ UINT8 control;
+ struct {
+ /*the order of these are flipped on the fit pc side to make it work*/
+ UINT8 fpgaChkSum :1;
+ UINT8 cRIOChkSum :1;
+ UINT8 resync : 1;
+ UINT8 fmsAttached:1;
+ UINT8 autonomous : 1;
+ UINT8 enabled : 1;
+ UINT8 notEStop : 1;
+ UINT8 reset : 1;
+ };
+ };
+ UINT8 dsDigitalIn;
+ UINT16 teamID;
+
+ char dsID_Alliance;
+ char dsID_Position;
+
+ union {
+ INT8 stick0Axes[6];
+ struct {
+ INT8 stick0Axis1;
+ INT8 stick0Axis2;
+ INT8 stick0Axis3;
+ INT8 stick0Axis4;
+ INT8 stick0Axis5;
+ INT8 stick0Axis6;
+ };
+ };
+ UINT16 stick0Buttons; // Left-most 4 bits are unused
+
+ union {
+ INT8 stick1Axes[6];
+ struct {
+ INT8 stick1Axis1;
+ INT8 stick1Axis2;
+ INT8 stick1Axis3;
+ INT8 stick1Axis4;
+ INT8 stick1Axis5;
+ INT8 stick1Axis6;
+ };
+ };
+ UINT16 stick1Buttons; // Left-most 4 bits are unused
+
+ union {
+ INT8 stick2Axes[6];
+ struct {
+ INT8 stick2Axis1;
+ INT8 stick2Axis2;
+ INT8 stick2Axis3;
+ INT8 stick2Axis4;
+ INT8 stick2Axis5;
+ INT8 stick2Axis6;
+ };
+ };
+ UINT16 stick2Buttons; // Left-most 4 bits are unused
+
+ union {
+ INT8 stick3Axes[6];
+ struct {
+ INT8 stick3Axis1;
+ INT8 stick3Axis2;
+ INT8 stick3Axis3;
+ INT8 stick3Axis4;
+ INT8 stick3Axis5;
+ INT8 stick3Axis6;
+ };
+ };
+ UINT16 stick3Buttons; // Left-most 4 bits are unused
+
+ //Analog inputs are 10 bit right-justified
+ UINT16 analog1;
+ UINT16 analog2;
+ UINT16 analog3;
+ UINT16 analog4;
+
+ UINT64 cRIOChecksum;
+ UINT32 FPGAChecksum0;
+ UINT32 FPGAChecksum1;
+ UINT32 FPGAChecksum2;
+ UINT32 FPGAChecksum3;
+
+ char versionData[8];
+};
+
+
+#endif
diff --git a/aos/atom_code/input/JoystickInput.cpp b/aos/atom_code/input/JoystickInput.cpp
new file mode 100644
index 0000000..6aeca4b
--- /dev/null
+++ b/aos/atom_code/input/JoystickInput.cpp
@@ -0,0 +1,66 @@
+#include "aos/atom_code/input/JoystickInput.h"
+
+#include "aos/aos_core.h"
+#include "aos/common/Configuration.h"
+#include "aos/common/network/ReceiveSocket.h"
+#include "aos/common/messages/RobotState.q.h"
+
+namespace aos {
+
+void JoystickInput::SetupButtons() {
+ for (int i = 0; i < 4; ++i) {
+ old_buttons[i] = buttons[i];
+ }
+ buttons[0] = control_data_.stick0Buttons;
+ buttons[1] = control_data_.stick1Buttons;
+ buttons[2] = control_data_.stick2Buttons;
+ buttons[3] = control_data_.stick3Buttons;
+
+ buttons[0] |= (control_data_.enabled << (ENABLED - 9)) |
+ (control_data_.autonomous << (AUTONOMOUS - 9)) |
+ (control_data_.fmsAttached << (FMS_ATTACHED - 9));
+
+ for (int j = 0; j < 4; ++j) {
+ for (int k = 1; k <= 12; ++k) {
+ if (PosEdge(j, k)) {
+ LOG(INFO, "PosEdge(%d, %d)\n", j, k);
+ }
+ if (NegEdge(j, k)) {
+ LOG(INFO, "NegEdge(%d, %d)\n", j, k);
+ }
+ }
+ }
+ if (PosEdge(0, ENABLED)) LOG(INFO, "PosEdge(ENABLED)\n");
+ if (NegEdge(0, ENABLED)) LOG(INFO, "NegEdge(ENABLED)\n");
+ if (PosEdge(0, AUTONOMOUS)) LOG(INFO, "PosEdge(AUTONOMOUS)\n");
+ if (NegEdge(0, AUTONOMOUS)) LOG(INFO, "NegEdge(AUTONOMOUS)\n");
+ if (PosEdge(0, FMS_ATTACHED)) LOG(INFO, "PosEdge(FMS_ATTACHED)\n");
+ if (NegEdge(0, FMS_ATTACHED)) LOG(INFO, "NegEdge(FMS_ATTACHED)\n");
+}
+
+void JoystickInput::Run() {
+ ReceiveSocket sock(NetworkPort::kDS);
+ while (true) {
+ if (sock.Recv(&control_data_, sizeof(control_data_)) == -1) {
+ LOG(WARNING, "socket receive failed\n");
+ continue;
+ }
+ SetupButtons();
+ if (!robot_state.MakeWithBuilder().enabled(Pressed(0, ENABLED)).
+ autonomous(Pressed(0, AUTONOMOUS)).
+ team_id(ntohs(control_data_.teamID)).Send()) {
+ LOG(WARNING, "sending robot_state failed\n");
+ }
+ if (robot_state.FetchLatest()) {
+ char state[1024];
+ robot_state->Print(state, sizeof(state));
+ LOG(DEBUG, "robot_state={%s}\n", state);
+ } else {
+ LOG(WARNING, "fetching robot_state failed\n");
+ }
+ RunIteration();
+ }
+}
+
+} // namespace aos
+
diff --git a/aos/atom_code/input/JoystickInput.h b/aos/atom_code/input/JoystickInput.h
new file mode 100644
index 0000000..de5de04
--- /dev/null
+++ b/aos/atom_code/input/JoystickInput.h
@@ -0,0 +1,45 @@
+#ifndef AOS_INPUT_JOYSTICK_INPUT_H_
+#define AOS_INPUT_JOYSTICK_INPUT_H_
+
+#include "FRCComm.h"
+
+namespace aos {
+
+// Class for implementing atom code that reads the joystick values from the
+// cRIO.
+// Designed for a subclass that implements RunIteration to be instantiated and
+// Runed.
+class JoystickInput {
+ private:
+ uint16_t buttons[4], old_buttons[4];
+ inline uint16_t MASK(int button) {
+ return 1 << ((button > 8) ? (button - 9) : (button + 7));
+ }
+ void SetupButtons();
+ protected:
+ FRCCommonControlData control_data_;
+
+ // Constants that retrieve data when used with joystick 0.
+ static const int ENABLED = 13;
+ static const int AUTONOMOUS = 14;
+ static const int FMS_ATTACHED = 15;
+ bool Pressed(int stick, int button) {
+ return buttons[stick] & MASK(button);
+ }
+ bool PosEdge(int stick, int button) {
+ return !(old_buttons[stick] & MASK(button)) && (buttons[stick] & MASK(button));
+ }
+ bool NegEdge(int stick, int button) {
+ return (old_buttons[stick] & MASK(button)) && !(buttons[stick] & MASK(button));
+ }
+
+ virtual void RunIteration() = 0;
+ public:
+ // Enters an infinite loop that reads values and calls RunIteration.
+ void Run();
+};
+
+} // namespace aos
+
+#endif
+
diff --git a/aos/atom_code/input/input.gyp b/aos/atom_code/input/input.gyp
new file mode 100644
index 0000000..e77fc47
--- /dev/null
+++ b/aos/atom_code/input/input.gyp
@@ -0,0 +1,14 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'joystick',
+ 'type': 'static_library',
+ 'sources': [
+ 'JoystickInput.cpp'
+ ],
+ 'dependencies': [
+ '<(AOS)/common/messages/messages.gyp:aos_queues',
+ ]
+ },
+ ],
+}
diff --git a/aos/atom_code/ipc_lib/aos_sync.c b/aos/atom_code/ipc_lib/aos_sync.c
new file mode 100644
index 0000000..a9a4779
--- /dev/null
+++ b/aos/atom_code/ipc_lib/aos_sync.c
@@ -0,0 +1,135 @@
+#include <stdio.h>
+#include <linux/futex.h>
+#include <unistd.h>
+#include <sys/syscall.h>
+#include <errno.h>
+#include "aos_sync.h"
+#include "cmpxchg.h"
+#include <stdint.h>
+#include <limits.h>
+#include <string.h>
+
+// this code is based on something that appears to be based on <http://www.akkadia.org/drepper/futex.pdf>, which also has a lot of useful information
+// should probably use <http://lxr.linux.no/linux+v2.6.34/Documentation/robust-futexes.txt> once it becomes available
+// <http://locklessinc.com/articles/futex_cheat_sheet/> and <http://locklessinc.com/articles/mutex_cv_futex/> are useful
+// <http://lwn.net/Articles/360699/> has a nice overview of futexes in late 2009 (fairly recent compared to everything else...)
+// can't use PRIVATE futex operations because they use the pid (or something) as part of the hash
+//
+// Values for a mutex:
+// 0 = unlocked
+// 1 = locked, not contended
+// 2 = locked, probably contended
+// Values for a condition:
+// 0 = unset
+// 1 = set
+
+static inline int sys_futex(mutex *addr1, int op, int val1, const struct timespec *timeout,
+ void *addr2, int val3) {
+ return syscall(SYS_futex, addr1, op, val1, timeout, addr2, val3);
+}
+
+static inline int mutex_get(mutex *m, uint8_t signals_fail, const
+ struct timespec *timeout) {
+ int c;
+ c = cmpxchg(m, 0, 1);
+ if (!c) return 0;
+ /* The lock is now contended */
+ if (c == 1) c = xchg(m, 2);
+ while (c) {
+ /* Wait in the kernel */
+ //printf("sync here %d\n", __LINE__);
+ if (sys_futex(m, FUTEX_WAIT, 2, timeout, NULL, 0) == -1) {
+ if (signals_fail && errno == EINTR) {
+ return 1;
+ }
+ if (timeout != NULL && errno == ETIMEDOUT) {
+ return 2;
+ }
+ }
+ //printf("sync here %d\n", __LINE__);
+ c = xchg(m, 2);
+ }
+ return 0;
+}
+int mutex_lock(mutex *m) {
+ return mutex_get(m, 1, NULL);
+}
+int mutex_lock_timeout(mutex *m, const struct timespec *timeout) {
+ return mutex_get(m, 1, timeout);
+}
+int mutex_grab(mutex *m) {
+ return mutex_get(m, 0, NULL);
+}
+
+int mutex_unlock(mutex *m) {
+ /* Unlock, and if not contended then exit. */
+ //printf("mutex_unlock(%p) => %d \n",m,*m);
+ switch (xchg(m, 0)) {
+ case 0:
+ fprintf(stderr, "sync: multiple unlock of %p. aborting\n", m);
+ printf("see stderr\n");
+ abort();
+ case 1:
+ //printf("mutex_unlock return(%p) => %d \n",m,*m);
+ return 0;
+ case 2:
+ if (sys_futex(m, FUTEX_WAKE, 1, NULL, NULL, 0) == -1) {
+ fprintf(stderr, "sync: waking 1 from %p failed with %d: %s\n",
+ m, errno, strerror(errno));
+ return -1;
+ } else {
+ return 0;
+ }
+ default:
+ fprintf(stderr, "sync: got a garbage value from mutex %p. aborting\n",
+ m);
+ printf("see stderr\n");
+ abort();
+ }
+}
+int mutex_trylock(mutex *m) {
+ /* Try to take the lock, if is currently unlocked */
+ unsigned c = cmpxchg(m, 0, 1);
+ if (!c) return 0;
+ return 1;
+}
+
+int condition_wait(mutex *m) {
+ if (*m) {
+ return 0;
+ }
+ if (sys_futex(m, FUTEX_WAIT, 0, NULL, NULL, 0) == -1) {
+ if (errno == EINTR) {
+ return 1;
+ } else if (errno != EWOULDBLOCK) {
+ return -1;
+ }
+ }
+ return 0;
+}
+int condition_wait_force(mutex *m) {
+ while (1) {
+ if (sys_futex(m, FUTEX_WAIT, *m, NULL, NULL, 0) == -1) {
+ if (errno != EWOULDBLOCK) { // if it was an actual problem
+ if (errno == EINTR) {
+ return 1;
+ } else {
+ return -1;
+ }
+ }
+ } else {
+ return 0;
+ }
+ }
+}
+inline int condition_set_value(mutex *m, mutex value) {
+ xchg(m, value);
+ return sys_futex(m, FUTEX_WAKE, INT_MAX, NULL, NULL, 0);
+}
+int condition_set(mutex *m) {
+ return condition_set_value(m, 1);
+}
+int condition_unset(mutex *m) {
+ return !xchg(m, 0);
+}
+
diff --git a/aos/atom_code/ipc_lib/aos_sync.h b/aos/atom_code/ipc_lib/aos_sync.h
new file mode 100644
index 0000000..3c66264
--- /dev/null
+++ b/aos/atom_code/ipc_lib/aos_sync.h
@@ -0,0 +1,63 @@
+#ifndef AOS_IPC_LIB_SYNC_H_
+#define AOS_IPC_LIB_SYNC_H_
+
+#include <stdlib.h>
+#include <signal.h>
+#include <stdint.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif // __cplusplus
+
+// TODO(brians) add client requests to make helgrind useful with this code
+// <http://www.valgrind.org/docs/manual/hg-manual.html#hg-manual.client-requests>
+// and <http://www.valgrind.org/docs/manual/drd-manual.html#drd-manual.clientreqs>
+// list the interesting ones
+
+// Have to align structs containing it to to sizeof(int).
+// Valid initial values for use with mutex_ functions are 0 (unlocked) and 1 (locked).
+// Valid initial values for use with condition_ functions are 0 (unset) and 1 (set).
+// The value should not be changed after multiple processes have started
+// accessing an instance except through the functions declared in this file.
+typedef volatile uint32_t mutex __attribute__((aligned(sizeof(int))));
+
+// All return -1 for other error (which will be in errno from futex(2)).
+
+// Returns 1 if interrupted by a signal.
+int mutex_lock(mutex *m) __attribute__((warn_unused_result));
+// Returns 2 if it timed out or 1 if interrupted by a signal.
+int mutex_lock_timeout(mutex *m, const struct timespec *timeout)
+ __attribute__((warn_unused_result));
+// Ignores signals. Can not fail.
+int mutex_grab(mutex *m);
+// Returns 1 for multiple unlocking and -1 if something bad happened and
+// whoever's waiting didn't get woken up.
+int mutex_unlock(mutex *m);
+// Returns 0 when successful in locking the mutex and 1 if somebody else has it
+// locked.
+int mutex_trylock(mutex *m) __attribute__((warn_unused_result));
+
+// The condition_ functions are similar to the mutex_ ones but different.
+// They are designed for signalling when something happens (possibly to
+// multiple listeners). A mutex manipulated with them can only be set or unset.
+
+// Wait for the condition to be set. Will return immediately if it's already set.
+// Returns 0 if successful or it was already set, 1 if interrupted by a signal, or -1.
+int condition_wait(mutex *m) __attribute__((warn_unused_result));
+// Will wait for the next condition_set, even if the condition is already set.
+// Returns 0 if successful, 1 if interrupted by a signal, or -1.
+int condition_wait_force(mutex *m) __attribute__((warn_unused_result));
+// Set the condition and wake up anybody waiting on it.
+// Returns the number that were woken or -1.
+int condition_set(mutex *m);
+// Same as above except lets something other than 1 be used as the final value.
+int condition_set_value(mutex *m, mutex value);
+// Unsets the condition.
+// Returns 0 if it was set before and 1 if it wasn't.
+int condition_unset(mutex *m);
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+
+#endif
diff --git a/aos/atom_code/ipc_lib/binheap.c b/aos/atom_code/ipc_lib/binheap.c
new file mode 100644
index 0000000..8eb024d
--- /dev/null
+++ b/aos/atom_code/ipc_lib/binheap.c
@@ -0,0 +1,125 @@
+#include "binheap.h"
+#include <stdlib.h>
+#include <stdio.h>
+
+#ifndef TESTING_ASSERT
+#define TESTING_ASSERT(...)
+#endif
+#define Error(x) TESTING_ASSERT(0, x)
+
+#define MinData (0)
+
+void Initialize( int Elements, PriorityQueue H )
+{
+ H->Capacity = Elements - 1;
+ H->Size = 0;
+ H->Elements[ 0 ] = MinData;
+}
+
+int Insert( ElementType X, PriorityQueue H )
+{
+ int i;
+
+ if( IsFull( H ) )
+ {
+ return -1;
+ }
+
+ for( i = ++H->Size; H->Elements[ i / 2 ] > X; i /= 2 )
+ H->Elements[ i ] = H->Elements[ i / 2 ];
+ H->Elements[ i ] = X;
+ return 0;
+}
+
+void Remove( ElementType X, PriorityQueue H )
+{
+ int i, Child, removed = 0;
+ ElementType LastElement;
+
+ for ( i = 1; i <= H->Size; ++i )
+ {
+ if( H->Elements[ i ] == X )
+ {
+ removed = i;
+ break;
+ }
+ }
+ if( removed == 0 )
+ {
+ fprintf(stderr, "could not find element %d to remove. not removing any\n", X);
+ return;
+ }
+
+ LastElement = H->Elements[ H->Size-- ];
+
+ for( i = removed; i * 2 <= H->Size; i = Child )
+ {
+ /* Find smaller child */
+ Child = i * 2;
+ if( Child != H->Size && H->Elements[ Child + 1 ]
+ < H->Elements[ Child ] )
+ Child++;
+
+ /* Percolate one level */
+ if( LastElement > H->Elements[ Child ] )
+ H->Elements[ i ] = H->Elements[ Child ];
+ else
+ break;
+ }
+ H->Elements[ i ] = LastElement;
+}
+
+ElementType DeleteMin( PriorityQueue H )
+{
+ int i, Child;
+ ElementType MinElement, LastElement;
+
+ if( IsEmpty( H ) )
+ {
+ Error( "Priority queue is empty" );
+ return H->Elements[ 0 ];
+ }
+ MinElement = H->Elements[ 1 ];
+ LastElement = H->Elements[ H->Size-- ];
+
+ for( i = 1; i * 2 <= H->Size; i = Child )
+ {
+ /* Find smaller child */
+ Child = i * 2;
+ if( Child != H->Size && H->Elements[ Child + 1 ]
+ < H->Elements[ Child ] )
+ Child++;
+
+ /* Percolate one level */
+ if( LastElement > H->Elements[ Child ] )
+ H->Elements[ i ] = H->Elements[ Child ];
+ else
+ break;
+ }
+ H->Elements[ i ] = LastElement;
+ return MinElement;
+}
+
+ElementType GetMin( PriorityQueue H )
+{
+ if( !IsEmpty( H ) )
+ return H->Elements[ 1 ];
+ Error( "Priority Queue is Empty" );
+ return H->Elements[ 0 ];
+}
+
+int IsEmpty( PriorityQueue H )
+{
+ return H->Size == 0;
+}
+
+int IsFull( PriorityQueue H )
+{
+ return H->Size == H->Capacity;
+}
+
+int GetSize( PriorityQueue H )
+{
+ return H->Size;
+}
+
diff --git a/aos/atom_code/ipc_lib/binheap.h b/aos/atom_code/ipc_lib/binheap.h
new file mode 100644
index 0000000..8c26f9f
--- /dev/null
+++ b/aos/atom_code/ipc_lib/binheap.h
@@ -0,0 +1,29 @@
+#ifndef _BinHeap_H
+#define _BinHeap_H
+
+#include <stdint.h>
+
+typedef uint8_t ElementType;
+struct HeapStruct;
+typedef struct HeapStruct *PriorityQueue;
+
+struct HeapStruct
+{
+ int Capacity;
+ int Size;
+ ElementType *Elements;
+};
+
+// Elements is the number allocated at H->Elements
+void Initialize( int Elements, PriorityQueue H );
+// 0 if successful, -1 if full
+int Insert( ElementType X, PriorityQueue H );
+void Remove( ElementType X, PriorityQueue H );
+ElementType DeleteMin( PriorityQueue H );
+ElementType GetMin( PriorityQueue H );
+int IsEmpty( PriorityQueue H );
+int IsFull( PriorityQueue H );
+int GetSize( PriorityQueue H );
+
+#endif
+
diff --git a/aos/atom_code/ipc_lib/binheap_test.cpp b/aos/atom_code/ipc_lib/binheap_test.cpp
new file mode 100644
index 0000000..62eecd4
--- /dev/null
+++ b/aos/atom_code/ipc_lib/binheap_test.cpp
@@ -0,0 +1,65 @@
+extern "C" {
+#include "binheap.h"
+}
+
+#include <gtest/gtest.h>
+
+class BinHeapTest : public testing::Test{
+ protected:
+ static const int TEST_ELEMENTS = 57;
+ PriorityQueue queue;
+ virtual void SetUp(){
+ queue = new HeapStruct();
+ queue->Elements = new uint8_t[TEST_ELEMENTS];
+ Initialize(TEST_ELEMENTS, queue);
+ }
+ virtual void TearDown(){
+ delete[] queue->Elements;
+ delete queue;
+ }
+};
+
+std::ostream& operator<< (std::ostream& o, uint8_t c){
+ return o<<(int)c;
+}
+
+testing::AssertionResult Contains(PriorityQueue queue, const uint8_t expected[], size_t length){
+ for(size_t i = 0; i < length; ++i){
+ //printf("expected[%d]=%d\n", i, expected[i]);
+ if(DeleteMin(queue) != expected[i]){
+ return testing::AssertionFailure() << "queue[" << i << "] != " << expected[i];
+ }
+ }
+ if(!IsEmpty(queue))
+ return testing::AssertionFailure() << "queue is longer than " << length;
+ return ::testing::AssertionSuccess();
+}
+
+TEST_F(BinHeapTest, SingleElement){
+ Insert(87, queue);
+ EXPECT_EQ(87, DeleteMin(queue));
+ EXPECT_TRUE(IsEmpty(queue));
+}
+TEST_F(BinHeapTest, MultipleElements){
+ Insert(54, queue);
+ Insert(1, queue);
+ Insert(0, queue);
+ Insert(255, queue);
+ Insert(123, queue);
+ uint8_t expected[] = {0, 1, 54, 123, 255};
+ EXPECT_TRUE(Contains(queue, expected, sizeof(expected)));
+}
+TEST_F(BinHeapTest, Removals){
+ Insert(54, queue);
+ Insert(1, queue);
+ Insert(0, queue);
+ Insert(255, queue);
+ Insert(123, queue);
+ Remove(255, queue);
+ Remove(0, queue);
+ Insert(222, queue);
+ Insert(67, queue);
+ uint8_t expected[] = {1, 54, 67, 123, 222};
+ EXPECT_TRUE(Contains(queue, expected, sizeof(expected)));
+}
+
diff --git a/aos/atom_code/ipc_lib/cmpxchg.h b/aos/atom_code/ipc_lib/cmpxchg.h
new file mode 100644
index 0000000..acb4a3c
--- /dev/null
+++ b/aos/atom_code/ipc_lib/cmpxchg.h
@@ -0,0 +1,153 @@
+#ifndef __ASM_CMPXCHG_H
+#define __ASM_CMPXCHG_H
+
+#include <stdint.h>
+
+//TODO implement xchg using gcc's atomic builtins (http://gcc.gnu.org/onlinedocs/gcc-4.1.1/gcc/Atomic-Builtins.html)
+//or maybe http://gcc.gnu.org/onlinedocs/gcc/_005f_005fatomic-Builtins.html
+//__atomic_fetch_sub looks promising
+
+#define cmpxchg(ptr, o, n) __sync_val_compare_and_swap(ptr, o, n)
+/*#define xchg(ptr, n) ({typeof(*ptr) r; \
+ do{ \
+ r = *ptr; \
+ }while(!__sync_bool_compare_and_swap(ptr, r, n)); \
+ r; \
+})*/
+
+# define LOCK "lock;"
+# define LOCK_PREFIX "lock;"
+
+#define xchg(ptr,v) ((__typeof__(*(ptr)))__xchg((unsigned long)(v),(ptr),sizeof(*(ptr))))
+
+#define __xg(x) ((volatile long long *)(x))
+
+/*static inline void set_64bit(volatile unsigned long *ptr, unsigned long val)
+{
+ *ptr = val;
+}
+
+#define _set_64bit set_64bit*/
+
+/*
+ * Note: no "lock" prefix even on SMP: xchg always implies lock anyway
+ * Note 2: xchg has side effect, so that attribute volatile is necessary,
+ * but generally the primitive is invalid, *ptr is output argument. --ANK
+ */
+static inline unsigned long __xchg(unsigned long x, volatile void * ptr, int size)
+{
+ switch (size) {
+ case 1:
+ __asm__ __volatile__("xchgb %b0,%1"
+ :"=q" (x)
+ :"m" (*__xg(ptr)), "0" (x)
+ :"memory");
+ break;
+ case 2:
+ __asm__ __volatile__("xchgw %w0,%1"
+ :"=r" (x)
+ :"m" (*__xg(ptr)), "0" (x)
+ :"memory");
+ break;
+ case 4:
+ __asm__ __volatile__("xchgl %k0,%1"
+ :"=r" (x)
+ :"m" (*__xg(ptr)), "0" (x)
+ :"memory");
+ break;
+ case 8:
+ __asm__ __volatile__("xchg %0,%1"
+ :"=r" (x)
+ :"m" (*__xg(ptr)), "0" (x)
+ :"memory");
+ break;
+ }
+ return x;
+}
+
+/*
+ * Atomic compare and exchange. Compare OLD with MEM, if identical,
+ * store NEW in MEM. Return the initial value in MEM. Success is
+ * indicated by comparing RETURN with OLD.
+ */
+
+#if 0
+
+#define __HAVE_ARCH_CMPXCHG 1
+
+static inline unsigned long __cmpxchg(volatile void *ptr, unsigned long old,
+ unsigned long new, int size)
+{
+ int32_t prev;
+ switch (size) {
+ case 1:
+ __asm__ __volatile__(LOCK_PREFIX "cmpxchgb %b1,%2"
+ : "=a"(prev)
+ : "q"(new), "m"(*__xg(ptr)), "0"(old)
+ : "memory");
+ return prev;
+ case 2:
+ __asm__ __volatile__(LOCK_PREFIX "cmpxchgw %w1,%2"
+ : "=a"(prev)
+ : "r"(new), "m"(*__xg(ptr)), "0"(old)
+ : "memory");
+ return prev;
+ case 4:
+ __asm__ __volatile__(LOCK_PREFIX "cmpxchgl %k1,%2"
+ : "=a"(prev)
+ : "r"(new), "m"(*__xg(ptr)), "0"(old)
+ : "memory");
+ return prev;
+ case 8:
+ __asm__ __volatile__("lock; cmpxchg %1,%2"
+ : "=a"(prev)
+ : "q"(new), "m"(*__xg(ptr)), "0"(old)
+ : "memory");
+ return prev;
+ }
+ return old;
+}
+
+/*
+static inline unsigned long __cmpxchg_local(volatile void *ptr,
+ unsigned long old, unsigned long new, int size)
+{
+ unsigned long prev;
+ switch (size) {
+ case 1:
+ __asm__ __volatile__("cmpxchgb %b1,%2"
+ : "=a"(prev)
+ : "q"(new), "m"(*__xg(ptr)), "0"(old)
+ : "memory");
+ return prev;
+ case 2:
+ __asm__ __volatile__("cmpxchgw %w1,%2"
+ : "=a"(prev)
+ : "r"(new), "m"(*__xg(ptr)), "0"(old)
+ : "memory");
+ return prev;
+ case 4:
+ __asm__ __volatile__("cmpxchgl %k1,%2"
+ : "=a"(prev)
+ : "r"(new), "m"(*__xg(ptr)), "0"(old)
+ : "memory");
+ return prev;
+ case 8:
+ __asm__ __volatile__("cmpxchgq %1,%2"
+ : "=a"(prev)
+ : "r"(new), "m"(*__xg(ptr)), "0"(old)
+ : "memory");
+ return prev;
+ }
+ return old;
+}*/
+
+#define cmpxchg(ptr,o,n)\
+ ((__typeof__(*(ptr)))__cmpxchg((ptr),(unsigned long)(o),\
+ (unsigned long)(n),sizeof(*(ptr))))
+/*#define cmpxchg_local(ptr,o,n)\
+ ((__typeof__(*(ptr)))__cmpxchg((ptr),(unsigned long)(o),\
+ (unsigned long)(n),sizeof(*(ptr))))*/
+#endif
+
+#endif
diff --git a/aos/atom_code/ipc_lib/core_lib.c b/aos/atom_code/ipc_lib/core_lib.c
new file mode 100644
index 0000000..d4988cc
--- /dev/null
+++ b/aos/atom_code/ipc_lib/core_lib.c
@@ -0,0 +1,53 @@
+#include <stdio.h>
+#include <stdlib.h>
+#include "shared_mem.h"
+#include "core_lib.h"
+#include <time.h>
+
+void init_shared_mem_core(aos_shm_core *shm_core) {
+ clock_gettime(CLOCK_REALTIME, &shm_core->identifier);
+ shm_core->queues.alloc_flag = 0;
+ shm_core->msg_alloc_lock = 0;
+ shm_core->queues.queue_list = NULL;
+ shm_core->queues.alloc_lock = 0;
+ aos_resource_entity_root_create();
+ for(int i = 0; i < AOS_RESOURCE_NUM; ++i){
+ aos_resource_init(i);
+ }
+}
+static inline uint8_t aos_8max(uint8_t l, uint8_t r) {
+ return (l > r) ? l : r;
+}
+void *shm_malloc_aligned(size_t length, uint8_t alignment) {
+ // minimum alignments from <http://software.intel.com/en-us/articles/data-alignment-when-migrating-to-64-bit-intel-architecture/>
+ if (length <= 1) {
+ alignment = aos_8max(alignment, 1);
+ } else if (length <= 2) {
+ alignment = aos_8max(alignment, 2);
+ } else if (length <= 4) {
+ alignment = aos_8max(alignment, 4);
+ } else if (length <= 8) {
+ alignment = aos_8max(alignment, 8);
+ } else if (length <= 16) {
+ alignment = aos_8max(alignment, 16);
+ } else {
+ alignment = aos_8max(alignment, (length >= 64) ? 64 : 16);
+ }
+
+ void *msg = NULL;
+ aos_shm_core *shm_core = global_core->mem_struct;
+ mutex_grab(&shm_core->msg_alloc_lock);
+ shm_core->msg_alloc = (uint8_t *)shm_core->msg_alloc - length;
+ const uint8_t align_extra = (uintptr_t)shm_core->msg_alloc % alignment;
+ shm_core->msg_alloc = (uint8_t *)shm_core->msg_alloc - align_extra;
+ msg = shm_core->msg_alloc;
+ if (msg <= global_core->shared_mem) {
+ fprintf(stderr, "core_lib: RAN OUT OF SHARED MEMORY!!!----------------------------------------------------------\n");
+ printf("if you didn't see the stderr output just then, you should\n");
+ abort();
+ }
+ //printf("alloc %p\n", msg);
+ mutex_unlock(&shm_core->msg_alloc_lock);
+ return msg;
+}
+
diff --git a/aos/atom_code/ipc_lib/core_lib.h b/aos/atom_code/ipc_lib/core_lib.h
new file mode 100644
index 0000000..1983f7a
--- /dev/null
+++ b/aos/atom_code/ipc_lib/core_lib.h
@@ -0,0 +1,55 @@
+#ifndef _AOS_CORE_LIB_H_
+#define _AOS_CORE_LIB_H_
+
+// required by resource.h
+// defined in shared_mem.c
+#ifdef __cplusplus
+extern "C" {
+#endif // __cplusplus
+extern struct aos_core *global_core;
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+
+#include "aos_sync.h"
+#include "queue.h"
+#include <stdint.h>
+#include "resource_core.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif // __cplusplus
+
+struct aos_queue_list_t;
+typedef struct aos_queue_hash_t {
+ int alloc_flag;
+ mutex alloc_lock;
+ struct aos_queue_list_t *queue_list;
+} aos_queue_hash;
+
+typedef struct aos_shm_core_t {
+ // clock_gettime(CLOCK_REALTIME, &identifier) gets called to identify
+ // this shared memory area
+ struct timespec identifier;
+ // gets 0-initialized at the start (as part of shared memory) and
+ // the owner sets as soon as it finishes setting stuff up
+ mutex creation_condition;
+ mutex msg_alloc_lock;
+ void *msg_alloc;
+ aos_queue_hash queues;
+ aos_resource_list resources;
+} aos_shm_core;
+
+void init_shared_mem_core(aos_shm_core *shm_core);
+
+void *shm_malloc_aligned(size_t length, uint8_t alignment);
+static void *shm_malloc(size_t length);
+static inline void *shm_malloc(size_t length) {
+ return shm_malloc_aligned(length, 0);
+}
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+
+#endif
diff --git a/aos/atom_code/ipc_lib/ipc_lib.gyp b/aos/atom_code/ipc_lib/ipc_lib.gyp
new file mode 100644
index 0000000..4dd0fa9
--- /dev/null
+++ b/aos/atom_code/ipc_lib/ipc_lib.gyp
@@ -0,0 +1,55 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'ipc_lib',
+ 'type': 'static_library',
+ 'sources': [
+ 'aos_sync.c',
+ 'binheap.c',
+ 'core_lib.c',
+ 'queue.c',
+ 'resource.c',
+ 'shared_mem.c',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:aos/ResourceList.h',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/build/aos.gyp:aos/ResourceList.h',
+ ],
+ },
+ {
+ 'target_name': 'binheap_test',
+ 'type': 'executable',
+ 'sources': [
+ 'binheap_test.cpp',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ {
+ 'target_name': 'resource_test',
+ 'type': 'executable',
+ 'sources': [
+ 'resource_test.cpp',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ {
+ 'target_name': 'ipc_queue_test',
+ 'type': 'executable',
+ 'sources': [
+ 'queue_test.cpp',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ ],
+}
diff --git a/aos/atom_code/ipc_lib/mutex.cpp b/aos/atom_code/ipc_lib/mutex.cpp
new file mode 100644
index 0000000..d1f0ef2
--- /dev/null
+++ b/aos/atom_code/ipc_lib/mutex.cpp
@@ -0,0 +1,37 @@
+#include "aos/common/mutex.h"
+
+#include <inttypes.h>
+#include <errno.h>
+
+#include "aos/aos_core.h"
+#include "aos/common/type_traits.h"
+
+namespace aos {
+
+Mutex::Mutex() : impl_(0) {
+ static_assert(shm_ok<Mutex>::value,
+ "Mutex is not safe for use in shared memory.");
+}
+
+// Lock and Unlock use the return values of mutex_lock/mutex_unlock
+// to determine whether the lock/unlock succeeded.
+
+void Mutex::Lock() {
+ if (mutex_grab(&impl_) != 0) {
+ LOG(FATAL, "mutex_grab(%p(=%"PRIu32")) failed because of %d: %s\n",
+ &impl_, impl_, errno, strerror(errno));
+ }
+}
+
+void Mutex::Unlock() {
+ if (mutex_unlock(&impl_) != 0) {
+ LOG(FATAL, "mutex_unlock(%p(=%"PRIu32")) failed because of %d: %s\n",
+ &impl_, impl_, errno, strerror(errno));
+ }
+}
+
+bool Mutex::TryLock() {
+ return mutex_trylock(&impl_) == 0;
+}
+
+} // namespace aos
diff --git a/aos/atom_code/ipc_lib/queue.c b/aos/atom_code/ipc_lib/queue.c
new file mode 100644
index 0000000..5cfd2ac
--- /dev/null
+++ b/aos/atom_code/ipc_lib/queue.c
@@ -0,0 +1,510 @@
+#include "aos/atom_code/ipc_lib/queue.h"
+#include "aos/atom_code/ipc_lib/queue_internal.h"
+
+#include <stdio.h>
+#include <string.h>
+#include <errno.h>
+#include <assert.h>
+
+#define READ_DEBUG 0
+#define WRITE_DEBUG 0
+#define REF_DEBUG 0
+
+static inline aos_msg_header *get_header(void *msg) {
+ return (aos_msg_header *)((uint8_t *)msg - sizeof(aos_msg_header));
+}
+static inline aos_queue *aos_core_alloc_queue() {
+ return shm_malloc_aligned(sizeof(aos_queue), sizeof(int));
+}
+static inline void *aos_alloc_msg(aos_msg_pool *pool) {
+ return shm_malloc(pool->msg_length);
+}
+
+// actually free the given message
+static inline int aos_free_msg(aos_msg_pool *pool, void *msg, aos_queue *queue) {
+#if REF_DEBUG
+ if (pool->pool_lock == 0) {
+ //LOG(WARNING, "unprotected\n");
+ }
+#endif
+ aos_msg_header *header = get_header(msg);
+ if (pool->pool[header->index] != header) { // if something's messed up
+ fprintf(stderr, "queue: something is very very wrong with queue %p."
+ " pool->pool(=%p)[header->index(=%d)] != header(=%p)\n",
+ queue, pool->pool, header->index, header);
+ printf("queue: see stderr\n");
+ abort();
+ }
+#if REF_DEBUG
+ printf("ref_free_count: %p\n", msg);
+#endif
+ --pool->used;
+
+ if (queue->recycle != NULL) {
+ void *const new_msg = aos_queue_get_msg(queue->recycle);
+ if (new_msg == NULL) {
+ fprintf(stderr, "queue: couldn't get a message"
+ " for recycle queue %p\n", queue->recycle);
+ } else {
+ // Take a message from recycle_queue and switch its
+ // header with the one being freed, which effectively
+ // switches which queue each message belongs to.
+ aos_msg_header *const new_header = get_header(new_msg);
+ // also switch the messages between the pools
+ pool->pool[header->index] = new_header;
+ if (mutex_lock(&queue->recycle->pool.pool_lock)) {
+ return -1;
+ }
+ queue->recycle->pool.pool[new_header->index] = header;
+ // swap the information in both headers
+ header_swap(header, new_header);
+ // don't unlock the other pool until all of its messages are valid
+ mutex_unlock(&queue->recycle->pool.pool_lock);
+ // use the header for new_msg which is now for this pool
+ header = new_header;
+ if (aos_queue_write_msg_free(queue->recycle,
+ (void *)msg, OVERRIDE) != 0) {
+ printf("queue: warning aos_queue_write_msg("
+ "%p(=queue(=%p)->recycle), %p, OVERRIDE)"
+ " failed\n",
+ queue->recycle, queue, msg);
+ }
+ msg = new_msg;
+ }
+ }
+
+ // where the one we're freeing was
+ int index = header->index;
+ header->index = -1;
+ if (index != pool->used) { // if we're not freeing the one on the end
+ // put the last one where the one we're freeing was
+ header = pool->pool[index] = pool->pool[pool->used];
+ // put the one we're freeing at the end
+ pool->pool[pool->used] = get_header(msg);
+ // update the former last one's index
+ header->index = index;
+ }
+ return 0;
+}
+// TODO(brians) maybe do this with atomic integer instructions so it doesn't have to lock/unlock pool_lock
+static inline int msg_ref_dec(void *msg, aos_msg_pool *pool, aos_queue *queue) {
+ if (msg == NULL) {
+ return 0;
+ }
+
+ int rv = 0;
+ if (mutex_lock(&pool->pool_lock)) {
+ return -1;
+ }
+ aos_msg_header *const header = get_header(msg);
+ header->ref_count --;
+ assert(header->ref_count >= 0);
+#if REF_DEBUG
+ printf("ref_dec_count: %p count=%d\n", msg, header->ref_count);
+#endif
+ if (header->ref_count == 0) {
+ rv = aos_free_msg(pool, msg, queue);
+ }
+ mutex_unlock(&pool->pool_lock);
+ return rv;
+}
+
+static inline int sigcmp(const aos_type_sig *sig1, const aos_type_sig *sig2) {
+ if (sig1->length != sig2->length) {
+ //LOG(DEBUG, "length mismatch 1=%d 2=%d\n", sig1->length, sig2->length);
+ return 0;
+ }
+ if (sig1->queue_length != sig2->queue_length) {
+ //LOG(DEBUG, "queue_length mismatch 1=%d 2=%d\n", sig1->queue_length, sig2->queue_length);
+ return 0;
+ }
+ if (sig1->hash != sig2->hash) {
+ //LOG(DEBUG, "hash mismatch 1=%d 2=%d\n", sig1->hash, sig2->hash);
+ return 0;
+ }
+ //LOG(DEBUG, "signature match\n");
+ return 1;
+}
+static inline aos_queue *aos_create_queue(const aos_type_sig *sig) {
+ aos_queue *const queue = aos_core_alloc_queue();
+ aos_msg_pool *const pool = &queue->pool;
+ pool->mem_length = sig->queue_length + EXTRA_MESSAGES;
+ pool->length = 0;
+ pool->used = 0;
+ pool->msg_length = sig->length + sizeof(aos_msg_header);
+ pool->pool = shm_malloc(sizeof(void *) * pool->mem_length);
+ aos_ring_buf *const buf = &queue->buf;
+ buf->length = sig->queue_length + 1;
+ if (buf->length < 2) { // TODO(brians) when could this happen?
+ buf->length = 2;
+ }
+ buf->data = shm_malloc(buf->length * sizeof(void *));
+ buf->start = 0;
+ buf->end = 0;
+ buf->msgs = 0;
+ buf->writable = 1;
+ buf->readable = 0;
+ buf->buff_lock = 0;
+ pool->pool_lock = 0;
+ queue->recycle = NULL;
+ return queue;
+}
+aos_queue *aos_fetch_queue(const char *name, const aos_type_sig *sig) {
+ //LOG(DEBUG, "Fetching the stupid queue: %s\n", name);
+ mutex_grab(&global_core->mem_struct->queues.alloc_lock);
+ aos_queue_list *list = global_core->mem_struct->queues.queue_list;
+ aos_queue_list *last = NULL;
+ while (list != NULL) {
+ // if we found a matching queue
+ if (strcmp(list->name, name) == 0 && sigcmp(&list->sig, sig)) {
+ mutex_unlock(&global_core->mem_struct->queues.alloc_lock);
+ return list->queue;
+ } else {
+ //LOG(DEBUG, "rejected queue %s strcmp=%d target=%s\n", (*list)->name, strcmp((*list)->name, name), name);
+ }
+ last = list;
+ list = list->next;
+ }
+ list = shm_malloc(sizeof(aos_queue_list));
+ if (last == NULL) {
+ global_core->mem_struct->queues.queue_list = list;
+ } else {
+ last->next = list;
+ }
+ list->sig = *sig;
+ const size_t name_size = strlen(name) + 1;
+ list->name = shm_malloc(name_size);
+ memcpy(list->name, name, name_size);
+ //LOG(INFO, "creating queue{name=%s, sig.length=%zd, sig.hash=%d, sig.queue_length=%d}\n", name, sig->length, sig->hash, sig->queue_length);
+ list->queue = aos_create_queue(sig);
+ //LOG(DEBUG, "Made the stupid queue: %s happy?\n", name);
+ list->next = NULL;
+ mutex_unlock(&global_core->mem_struct->queues.alloc_lock);
+ return list->queue;
+}
+aos_queue *aos_fetch_queue_recycle(const char *name, const aos_type_sig *sig,
+ const aos_type_sig *recycle_sig, aos_queue **recycle) {
+ if (sig->length != recycle_sig->length || sig->hash == recycle_sig->hash) {
+ *recycle = NULL;
+ return NULL;
+ }
+ aos_queue *const r = aos_fetch_queue(name, sig);
+ r->recycle = aos_fetch_queue(name, recycle_sig);
+ if (r == r->recycle) {
+ fprintf(stderr, "queue: r->recycle(=%p) == r(=%p)\n", r->recycle, r);
+ printf("see stderr\n");
+ abort();
+ }
+ *recycle = r->recycle;
+ return r;
+}
+
+int aos_queue_write_msg(aos_queue *queue, void *msg, int opts) {
+#if WRITE_DEBUG
+ printf("queue: write_msg(%p, %p, %d)\n", queue, msg, opts);
+#endif
+ int rv = 0;
+ if (msg == NULL || msg < (void *)global_core->mem_struct ||
+ msg > (void *)((intptr_t)global_core->mem_struct + global_core->size)) {
+ fprintf(stderr, "queue: attempt to write bad message %p to %p. aborting\n",
+ msg, queue);
+ printf("see stderr\n");
+ abort();
+ }
+ aos_ring_buf *const buf = &queue->buf;
+ if (mutex_lock(&buf->buff_lock)) {
+#if WRITE_DEBUG
+ printf("queue: locking buff_lock of %p failed\n", buf);
+#endif
+ return -1;
+ }
+ int new_end = (buf->end + 1) % buf->length;
+ while (new_end == buf->start) {
+ if (opts & NON_BLOCK) {
+#if WRITE_DEBUG
+ printf("queue: not blocking on %p. returning -1\n", queue);
+#endif
+ mutex_unlock(&buf->buff_lock);
+ return -1;
+ } else if (opts & OVERRIDE) {
+#if WRITE_DEBUG
+ printf("queue: overriding on %p\n", queue);
+#endif
+ // avoid leaking the message that we're going to overwrite
+ msg_ref_dec(buf->data[buf->start], &queue->pool, queue);
+ buf->start = (buf->start + 1) % buf->length;
+ } else { // BLOCK
+ mutex_unlock(&buf->buff_lock);
+#if WRITE_DEBUG
+ printf("queue: going to wait for writable(=%p) of %p\n",
+ &buf->writable, queue);
+#endif
+ if (condition_wait(&buf->writable)) {
+#if WRITE_DEBUG
+ printf("queue: waiting for writable(=%p) of %p failed\n",
+ &buf->writable, queue);
+#endif
+ return -1;
+ }
+#if WRITE_DEBUG
+ printf("queue: going to re-lock buff_lock of %p to write\n", queue);
+#endif
+ if (mutex_lock(&buf->buff_lock)) {
+#if WRITE_DEBUG
+ printf("queue: error locking buff_lock of %p\n", queue);
+#endif
+ return -1;
+ }
+ }
+ new_end = (buf->end + 1) % buf->length;
+ }
+ buf->data[buf->end] = msg;
+ ++buf->msgs;
+ buf->end = new_end;
+ mutex_unlock(&buf->buff_lock);
+#if WRITE_DEBUG
+ printf("queue: setting readable(=%p) of %p\n", &buf->readable, queue);
+#endif
+ condition_set(&buf->readable);
+ if (((buf->end + 1) % buf->length) == buf->start) { // if it's now full
+ condition_unset(&buf->writable);
+ }
+#if WRITE_DEBUG
+ printf("queue: write returning %d on queue %p\n", rv, queue);
+#endif
+ return rv;
+}
+
+int aos_queue_free_msg(aos_queue *queue, const void *msg) {
+ // TODO(brians) get rid of this
+ void *msg_temp;
+ memcpy(&msg_temp, &msg, sizeof(msg_temp));
+ return msg_ref_dec(msg_temp, &queue->pool, queue);
+}
+// Deals with setting/unsetting readable and writable.
+// Should be called after buff_lock has been unlocked.
+// read is whether or not this read call read one off the queue
+static inline void aos_read_msg_common_end(aos_ring_buf *const buf, int read) {
+ if (read) {
+ condition_set(&buf->writable);
+ if (buf->start == buf->end) {
+ condition_unset(&buf->readable);
+ }
+ }
+}
+// Returns with buff_lock locked and a readable message in buf.
+// Returns -1 for error (if it returns -1, buff_lock will be unlocked).
+static inline int aos_queue_read_msg_common(int opts, aos_ring_buf *const buf,
+ aos_queue *const queue, int *index) {
+#if !READ_DEBUG
+ (void)queue;
+#endif
+ if (mutex_lock(&buf->buff_lock)) {
+#if READ_DEBUG
+ printf("queue: couldn't lock buff_lock of %p\n", queue);
+#endif
+ return -1;
+ }
+ while (buf->start == buf->end || ((index != NULL) && buf->msgs <= *index)) {
+ mutex_unlock(&buf->buff_lock);
+ if (opts & NON_BLOCK) {
+#if READ_DEBUG
+ printf("queue: not going to block waiting on %p\n", queue);
+#endif
+ return -1;
+ } else { // BLOCK
+#if READ_DEBUG
+ printf("queue: going to wait for readable(=%p) of %p\n",
+ &buf->readable, queue);
+#endif
+ // wait for a message to become readable
+ if ((index == NULL) ? condition_wait(&buf->readable) :
+ condition_wait_force(&buf->readable)) {
+#if READ_DEBUG
+ printf("queue: waiting for readable(=%p) of %p failed\n",
+ &buf->readable, queue);
+#endif
+ return -1;
+ }
+ }
+#if READ_DEBUG
+ printf("queue: going to re-lock buff_lock of %p to read\n", queue);
+#endif
+ if (mutex_lock(&buf->buff_lock)) {
+#if READ_DEBUG
+ printf("couldn't re-lock buff_lock of %p\n", queue);
+#endif
+ return -1;
+ }
+ }
+#if READ_DEBUG
+ printf("queue: read start=%d end=%d from %p\n", buf->start, buf->end, queue);
+#endif
+ return 0;
+}
+// handles reading with PEEK
+static inline void *read_msg_peek(aos_ring_buf *const buf, int opts, int start) {
+ void *ret;
+ if (opts & FROM_END) {
+ int pos = buf->end - 1;
+ if (pos < 0) { // if it needs to wrap
+ pos = buf->length - 1;
+ }
+#if READ_DEBUG
+ printf("queue: reading from line %d: %d\n", __LINE__, pos);
+#endif
+ ret = buf->data[pos];
+ } else {
+#if READ_DEBUG
+ printf("queue: reading from line %d: %d\n", __LINE__, start);
+#endif
+ ret = buf->data[start];
+ }
+ aos_msg_header *const header = get_header(ret);
+ header->ref_count ++;
+#if REF_DEBUG
+ printf("ref inc count: %p\n", ret);
+#endif
+ return ret;
+}
+const void *aos_queue_read_msg(aos_queue *queue, int opts) {
+#if READ_DEBUG
+ printf("queue: read_msg(%p, %d)\n", queue, opts);
+#endif
+ void *msg = NULL;
+ aos_ring_buf *const buf = &queue->buf;
+ if (aos_queue_read_msg_common(opts, buf, queue, NULL) == -1) {
+#if READ_DEBUG
+ printf("queue: common returned -1 for %p\n", queue);
+#endif
+ return NULL;
+ }
+ if (opts & PEEK) {
+ msg = read_msg_peek(buf, opts, buf->start);
+ } else {
+ if (opts & FROM_END) {
+ while (1) {
+#if READ_DEBUG
+ printf("queue: start of c2 of %p\n", queue);
+#endif
+ // This loop pulls each message out of the buffer.
+ const int pos = buf->start;
+ buf->start = (buf->start + 1) % buf->length;
+ // if this is the last one
+ if (buf->start == buf->end) {
+#if READ_DEBUG
+ printf("queue: reading from c2: %d\n", pos);
+#endif
+ msg = buf->data[pos];
+ break;
+ }
+ // it's not going to be in the queue any more
+ msg_ref_dec(buf->data[pos], &queue->pool, queue);
+ }
+ } else {
+#if READ_DEBUG
+ printf("queue: reading from d2: %d\n", buf->start);
+#endif
+ msg = buf->data[buf->start];
+ buf->start = (buf->start + 1) % buf->length;
+ }
+ }
+ mutex_unlock(&buf->buff_lock);
+ aos_read_msg_common_end(buf, !(opts & PEEK));
+#if READ_DEBUG
+ printf("queue: read returning %p\n", msg);
+#endif
+ return msg;
+}
+const void *aos_queue_read_msg_index(aos_queue *queue, int opts, int *index) {
+#if READ_DEBUG
+ printf("queue: read_msg_index(%p, %d, %p(*=%d))\n", queue, opts, index, *index);
+#endif
+ void *msg = NULL;
+ aos_ring_buf *const buf = &queue->buf;
+ if (aos_queue_read_msg_common(opts, buf, queue, index) == -1) {
+#if READ_DEBUG
+ printf("queue: common returned -1\n");
+#endif
+ return NULL;
+ }
+ // TODO(parker): Handle integer wrap on the index.
+ const int offset = buf->msgs - *index;
+ int my_start = buf->end - offset;
+ if (offset >= buf->length) { // if we're behind the available messages
+ // catch index up to the last available message
+ *index += buf->start - my_start;
+ // and that's the one we're going to read
+ my_start = buf->start;
+ }
+ if (my_start < 0) { // if we want to read off the end of the buffer
+ // unwrap where we're going to read from
+ my_start += buf->length;
+ }
+ if (opts & PEEK) {
+ msg = read_msg_peek(buf, opts, my_start);
+ } else {
+ if (opts & FROM_END) {
+#if READ_DEBUG
+ printf("queue: start of c1 of %p\n", queue);
+#endif
+ int pos = buf->end - 1;
+ if (pos < 0) { // if it wrapped
+ pos = buf->length - 1; // unwrap it
+ }
+#if READ_DEBUG
+ printf("queue: reading from c1: %d\n", pos);
+#endif
+ msg = buf->data[pos];
+ *index = buf->msgs;
+ } else {
+#if READ_DEBUG
+ printf("queue: reading from d1: %d\n", my_start);
+#endif
+ msg = buf->data[my_start];
+ ++(*index);
+ }
+ aos_msg_header *const header = get_header(msg);
+ ++header->ref_count;
+#if REF_DEBUG
+ printf("ref_inc_count: %p\n", msg);
+#endif
+ }
+ mutex_unlock(&buf->buff_lock);
+ // this function never consumes one off the queue
+ aos_read_msg_common_end(buf, 0);
+ return msg;
+}
+static inline void *aos_pool_get_msg(aos_msg_pool *pool) {
+ if (mutex_lock(&pool->pool_lock)) {
+ return NULL;
+ }
+ void *msg;
+ if (pool->length - pool->used > 0) {
+ msg = pool->pool[pool->used];
+ } else {
+ if (pool->length >= pool->mem_length) {
+ //TODO(brians) log this if it isn't the log queue
+ fprintf(stderr, "queue: overused_pool\n");
+ msg = NULL;
+ goto exit;
+ }
+ msg = pool->pool[pool->length] = aos_alloc_msg(pool);
+ ++pool->length;
+ }
+ aos_msg_header *const header = msg;
+ msg = (uint8_t *)msg + sizeof(aos_msg_header);
+ header->ref_count = 1;
+#if REF_DEBUG
+ printf("ref alloc: %p\n", msg);
+#endif
+ header->index = pool->used;
+ ++pool->used;
+exit:
+ mutex_unlock(&pool->pool_lock);
+ return msg;
+}
+void *aos_queue_get_msg(aos_queue *queue) {
+ return aos_pool_get_msg(&queue->pool);
+}
+
diff --git a/aos/atom_code/ipc_lib/queue.h b/aos/atom_code/ipc_lib/queue.h
new file mode 100644
index 0000000..4c279e1
--- /dev/null
+++ b/aos/atom_code/ipc_lib/queue.h
@@ -0,0 +1,134 @@
+#ifndef AOS_IPC_LIB_QUEUE_H_
+#define AOS_IPC_LIB_QUEUE_H_
+
+#include "shared_mem.h"
+#include "aos_sync.h"
+
+// TODO(brians) add valgrind client requests to the queue and shared_mem_malloc
+// code to make checking for leaks work better
+// <http://www.valgrind.org/docs/manual/mc-manual.html#mc-manual.mempools>
+// describes how
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+// Queues are the primary way to use shared memory. Basic use consists of
+// initializing an aos_type_sig and then calling aos_fetch_queue on it.
+// This aos_queue* can then be used to get a message and write it or to read a
+// message.
+// Queues (as the name suggests) are a FIFO stack of messages. Each combination
+// of name and aos_type_sig will result in a different queue, which means that
+// if you only recompile some code that uses differently sized messages, it will
+// simply use a different queue than the old code.
+//
+// Any pointers returned from these functions can be safely passed to other
+// processes because they are all shared memory pointers.
+// IMPORTANT: Any message pointer must be passed back in some way
+// (aos_queue_free_msg and aos_queue_write_msg are common ones) or the
+// application will leak shared memory.
+// NOTE: Taking a message from read_msg and then passing it to write_msg might
+// work, but it is not guaranteed to.
+
+typedef struct aos_type_sig_t {
+ size_t length; // sizeof(message)
+ int hash; // can differentiate multiple otherwise identical queues
+ int queue_length; // how many messages the queue can hold
+} aos_type_sig;
+
+// Structures that are opaque to users (defined in queue_internal.h).
+typedef struct aos_queue_list_t aos_queue_list;
+typedef struct aos_queue_t aos_queue;
+
+// Retrieves (and creates if necessary) a queue. Each combination of name and
+// signature refers to a completely independent queue.
+aos_queue *aos_fetch_queue(const char *name, const aos_type_sig *sig);
+// Same as above, except sets up the returned queue so that it will put messages
+// on *recycle (retrieved with recycle_sig) when they are freed (after they have
+// been released by all other readers/writers and are not in the queue).
+// The length of recycle_sig determines how many freed messages will be kept.
+// Other code can retrieve recycle_sig and sig separately. However, any frees
+// made using aos_fetch_queue with only sig before the recycle queue has been
+// associated with it will not go on to the recyce queue.
+// Will return NULL for both queues if sig->length != recycle_sig->length or
+// sig->hash == recycle_sig->hash (just to be safe).
+// NOTE: calling this function with the same sig but multiple recycle_sig s
+// will result in each freed message being put onto an undefined recycle_sig.
+aos_queue *aos_fetch_queue_recycle(const char *name, const aos_type_sig *sig,
+ const aos_type_sig *recycle_sig, aos_queue **recycle);
+
+// Constants for passing to opts arguments.
+// #defines so that c code can use queues
+// The non-conflicting ones can be combined with bitwise-or.
+// TODO(brians) prefix these?
+//
+// Causes the returned message to be left in the queue.
+// For reading only.
+#define PEEK 0x0001
+// Reads the last message in the queue instead of just the next one.
+// NOTE: This removes all of the messages until the last one from the queue
+// (which means that nobody else will read them). However, PEEK means to not
+// remove any from the queue, including the ones that are skipped.
+// For reading only.
+#define FROM_END 0x0002
+// Causes reads to return NULL and writes to fail instead of waiting.
+// For reading and writing.
+#define NON_BLOCK 0x0004
+// Causes things to block.
+// IMPORTANT: #defined to 0 so that it is the default. This has to stay.
+// For reading and writing.
+#define BLOCK 0x0000
+// Causes writes to overwrite the oldest message in the queue instead of
+// blocking.
+// For writing only.
+#define OVERRIDE 0x0008
+
+// Frees a message. Does nothing if msg is NULL.
+int aos_queue_free_msg(aos_queue *queue, const void *msg);
+
+// Writes a message into the queue.
+// NOTE: msg must point to at least the length of this queue's worth of valid
+// data to write
+// IMPORTANT: if this returns -1, then the caller must do something with msg
+// (like free it)
+int aos_queue_write_msg(aos_queue *queue, void *msg, int opts);
+// Exactly the same as aos_queue_write_msg, except it automatically frees the
+// message if writing fails.
+static inline int aos_queue_write_msg_free(aos_queue *queue, void *msg, int opts) {
+ const int ret = aos_queue_write_msg(queue, msg, opts);
+ if (ret != 0) {
+ aos_queue_free_msg(queue, msg);
+ }
+ return ret;
+}
+
+// Reads a message out of the queue.
+// The return value will have at least the length of this queue's worth of valid
+// data where it's pointing to.
+// The return value is const because other people might be viewing the same
+// messsage. Do not cast the const away!
+// IMPORTANT: The return value (if not NULL) must eventually be passed to
+// aos_queue_free_msg.
+const void *aos_queue_read_msg(aos_queue *buf, int opts);
+// Exactly the same as aos_queue_read_msg, except it will never return the same
+// message twice with the same index argument. However, it may not return some
+// messages that pass through the queue.
+// *index should start as 0. index does not have to be in shared memory, but it
+// can be
+const void *aos_queue_read_msg_index(aos_queue *queue, int opts, int *index);
+
+// Retrieves ("allocates") a message that can then be written to the queue.
+// NOTE: the return value will be completely uninitialized
+// The return value will have at least the length of this queue's worth of valid
+// data where it's pointing to.
+// Returns NULL for error.
+// IMPORTANT: The return value (if not NULL) must eventually be passed to
+// aos_queue_free_msg.
+void *aos_queue_get_msg(aos_queue *queue);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
diff --git a/aos/atom_code/ipc_lib/queue_internal.h b/aos/atom_code/ipc_lib/queue_internal.h
new file mode 100644
index 0000000..e6b23ef
--- /dev/null
+++ b/aos/atom_code/ipc_lib/queue_internal.h
@@ -0,0 +1,62 @@
+#ifndef AOS_IPC_LIB_QUEUE_INTERNAL_H_
+#define AOS_IPC_LIB_QUEUE_INTERNAL_H_
+
+#include "shared_mem.h"
+#include "aos_sync.h"
+
+// Should only be used by queue.c. Contains definitions of the structures
+// it uses.
+
+// The number of extra messages the pool associated with each queue will be able
+// to hold (for readers who are slow about freeing them).
+#define EXTRA_MESSAGES 20
+
+typedef struct aos_msg_header_t {
+ int ref_count;
+ int index; // in the pool
+} aos_msg_header;
+static inline void header_swap(aos_msg_header *l, aos_msg_header *r) {
+ aos_msg_header tmp;
+ tmp.ref_count = l->ref_count;
+ tmp.index = l->index;
+ l->ref_count = r->ref_count;
+ l->index = r->index;
+ r->ref_count = tmp.ref_count;
+ r->index = tmp.index;
+}
+
+struct aos_queue_list_t {
+ char *name;
+ aos_type_sig sig;
+ aos_queue *queue;
+ aos_queue_list *next;
+};
+
+typedef struct aos_ring_buf_t {
+ mutex buff_lock; // the main lock protecting operations on this buffer
+ // conditions
+ mutex writable;
+ mutex readable;
+ int length; // max index into data + 1
+ int start; // is an index into data
+ int end; // is an index into data
+ int msgs; // that have passed through
+ void **data; // array of messages (w/ headers)
+} aos_ring_buf;
+
+typedef struct aos_msg_pool_t {
+ mutex pool_lock;
+ size_t msg_length;
+ int mem_length; // the number of messages
+ int used; // number of messages
+ int length; // number of allocated messages
+ void **pool; // array of messages
+} aos_msg_pool;
+
+struct aos_queue_t {
+ aos_msg_pool pool;
+ aos_ring_buf buf;
+ aos_queue *recycle;
+};
+
+#endif
diff --git a/aos/atom_code/ipc_lib/queue_test.cpp b/aos/atom_code/ipc_lib/queue_test.cpp
new file mode 100644
index 0000000..d4eb700
--- /dev/null
+++ b/aos/atom_code/ipc_lib/queue_test.cpp
@@ -0,0 +1,404 @@
+#include <unistd.h>
+#include <sys/mman.h>
+#include <inttypes.h>
+
+#include <ostream>
+#include <memory>
+#include <map>
+
+#include "gtest/gtest.h"
+
+#include "aos/aos_core.h"
+#include "aos/atom_code/ipc_lib/sharedmem_test_setup.h"
+#include "aos/common/type_traits.h"
+
+using testing::AssertionResult;
+using testing::AssertionSuccess;
+using testing::AssertionFailure;
+
+// IMPORTANT: Some of the functions that do test predicate functions allocate
+// shared memory (and don't free it).
+class QueueTest : public SharedMemTestSetup {
+ protected:
+ static const size_t kFailureSize = 400;
+ static char *fatal_failure;
+ private:
+ // This gets registered right after the fork, so it will get run before any
+ // exit handlers that had already been registered.
+ static void ExitExitHandler() {
+ _exit(EXIT_SUCCESS);
+ }
+ enum class ResultType : uint8_t {
+ NotCalled,
+ Called,
+ Returned,
+ };
+ const std::string ResultTypeString(volatile const ResultType &result) {
+ switch (result) {
+ case ResultType::Returned:
+ return "Returned";
+ case ResultType::Called:
+ return "Called";
+ case ResultType::NotCalled:
+ return "NotCalled";
+ default:
+ return std::string("unknown(" + static_cast<uint8_t>(result)) + ")";
+ }
+ }
+ static_assert(aos::shm_ok<ResultType>::value, "this will get put in shared memory");
+ // Gets allocated in shared memory so it has to be volatile.
+ template<typename T> struct FunctionToCall {
+ ResultType result;
+ bool expected;
+ void (*function)(T*, char*);
+ T *arg;
+ volatile char failure[kFailureSize];
+ };
+ template<typename T> static void Hangs_(volatile FunctionToCall<T> *const to_call) {
+ to_call->result = ResultType::Called;
+ to_call->function(to_call->arg, const_cast<char *>(to_call->failure));
+ to_call->result = ResultType::Returned;
+ }
+
+ static const long kMsToNs = 1000000;
+ // The number of ms after which a function is considered to have hung.
+ // Must be < 1000.
+ static const long kHangTime = 10;
+ static const unsigned int kForkSleep = 0; // how many seconds to sleep after forking
+
+ // Represents a process that has been forked off. The destructor kills the
+ // process and wait(2)s for it.
+ class ForkedProcess {
+ const pid_t pid_;
+ mutex *const lock_;
+ public:
+ ForkedProcess(pid_t pid, mutex *lock) : pid_(pid), lock_(lock) {};
+ ~ForkedProcess() {
+ if (kill(pid_, SIGINT) == -1) {
+ if (errno == ESRCH) {
+ printf("process %jd was already dead\n", static_cast<intmax_t>(pid_));
+ } else {
+ fprintf(stderr, "kill(SIGKILL, %jd) failed with %d: %s\n",
+ static_cast<intmax_t>(pid_), errno, strerror(errno));
+ }
+ return;
+ }
+ const pid_t ret = wait(NULL);
+ if (ret == -1) {
+ fprintf(stderr, "wait(NULL) failed."
+ " child %jd might still be alive\n",
+ static_cast<intmax_t>(pid_));
+ } else if (ret == 0) {
+ fprintf(stderr, "child %jd wasn't waitable. it might still be alive\n",
+ static_cast<intmax_t>(pid_));
+ } else if (ret != pid_) {
+ fprintf(stderr, "child %d is dead, but child %jd might still be alive\n",
+ ret, static_cast<intmax_t>(pid_));
+ }
+ }
+
+ enum class JoinResult {
+ Finished, Hung, Error
+ };
+ JoinResult Join(long timeout = kHangTime) {
+ timespec ts{kForkSleep, timeout * kMsToNs};
+ switch (mutex_lock_timeout(lock_, &ts)) {
+ case 2:
+ return JoinResult::Hung;
+ case 0:
+ return JoinResult::Finished;
+ default:
+ return JoinResult::Error;
+ }
+ }
+ } __attribute__((unused));
+
+ // Member variables for HangsFork and HangsCheck.
+ typedef uint8_t ChildID;
+ static void ReapExitHandler() {
+ for (auto it = children_.begin(); it != children_.end(); ++it) {
+ delete it->second;
+ }
+ }
+ static std::map<ChildID, ForkedProcess *> children_;
+ std::map<ChildID, volatile FunctionToCall<void> *> to_calls_;
+
+ void SetUp() {
+ SharedMemTestSetup::SetUp();
+ fatal_failure = reinterpret_cast<char *>(shm_malloc(sizeof(fatal_failure)));
+ static bool registered = false;
+ if (!registered) {
+ atexit(ReapExitHandler);
+ registered = true;
+ }
+ }
+
+ protected:
+ // Function gets called with arg in a forked process.
+ // Leaks shared memory.
+ // the attribute is in the middle to make gcc happy
+ template<typename T> __attribute__((warn_unused_result))
+ std::unique_ptr<ForkedProcess> ForkExecute(void (*function)(T*), T *arg) {
+ mutex *lock = reinterpret_cast<mutex *>(shm_malloc_aligned(
+ sizeof(*lock), sizeof(int)));
+ *lock = 1;
+ const pid_t pid = fork();
+ switch (pid) {
+ case 0: // child
+ if (kForkSleep != 0) {
+ printf("pid %jd sleeping for %u\n", static_cast<intmax_t>(getpid()),
+ kForkSleep);
+ sleep(kForkSleep);
+ }
+ atexit(ExitExitHandler);
+ function(arg);
+ mutex_unlock(lock);
+ exit(EXIT_SUCCESS);
+ case -1: // parent failure
+ printf("fork() failed with %d: %s\n", errno, strerror(errno));
+ return std::unique_ptr<ForkedProcess>();
+ default: // parent
+ return std::unique_ptr<ForkedProcess>(new ForkedProcess(pid, lock));
+ }
+ }
+
+ // Checks whether or not the given function hangs.
+ // expected is whether to return success or failure if the function hangs
+ // NOTE: There are other reasons for it to return a failure than the function
+ // doing the wrong thing.
+ // Leaks shared memory.
+ template<typename T> AssertionResult Hangs(void (*function)(T*, char*), T *arg,
+ bool expected) {
+ AssertionResult fork_result(HangsFork<T>(function, arg, expected, 0));
+ if (!fork_result) {
+ return fork_result;
+ }
+ return HangsCheck(0);
+ }
+ // Starts the first part of Hangs.
+ // Use HangsCheck to get the result.
+ // Returns whether the fork succeeded or not, NOT whether or not the hang
+ // check succeeded.
+ template<typename T> AssertionResult HangsFork(void (*function)(T*, char *), T *arg,
+ bool expected, ChildID id) {
+ static_assert(aos::shm_ok<FunctionToCall<T>>::value,
+ "this is going into shared memory");
+ volatile FunctionToCall<T> *const to_call = reinterpret_cast<FunctionToCall<T> *>(
+ shm_malloc_aligned(sizeof(*to_call), sizeof(int)));
+ to_call->result = ResultType::NotCalled;
+ to_call->function = function;
+ to_call->arg = arg;
+ to_call->expected = expected;
+ to_call->failure[0] = '\0';
+ static_cast<volatile char *>(fatal_failure)[0] = '\0';
+ children_[id] = ForkExecute(Hangs_, to_call).release();
+ if (!children_[id]) return AssertionFailure() << "ForkExecute failed";
+ to_calls_[id] = reinterpret_cast<volatile FunctionToCall<void> *>(to_call);
+ return AssertionSuccess();
+ }
+ // Checks whether or not a function hung like it was supposed to.
+ // Use HangsFork first.
+ // NOTE: calls to HangsFork and HangsCheck with the same id argument will
+ // correspond, but they do not nest. Also, id 0 is used by Hangs.
+ // Return value is the same as Hangs.
+ AssertionResult HangsCheck(ChildID id) {
+ std::unique_ptr<ForkedProcess> child(children_[id]);
+ children_.erase(id);
+ const ForkedProcess::JoinResult result = child->Join();
+ if (to_calls_[id]->failure[0] != '\0') {
+ return AssertionFailure() << "function says: "
+ << const_cast<char *>(to_calls_[id]->failure);
+ }
+ if (result == ForkedProcess::JoinResult::Finished) {
+ return !to_calls_[id]->expected ? AssertionSuccess() : (AssertionFailure()
+ << "something happened and the the test only got to "
+ << ResultTypeString(to_calls_[id]->result));
+ } else {
+ if (to_calls_[id]->result == ResultType::Called) {
+ return to_calls_[id]->expected ? AssertionSuccess() : AssertionFailure();
+ } else {
+ return AssertionFailure() << "something weird happened";
+ }
+ }
+ }
+#define EXPECT_HANGS(function, arg) \
+ EXPECT_HANGS_COND(function, arg, true, EXPECT_TRUE)
+#define EXPECT_RETURNS(function, arg) \
+ EXPECT_HANGS_COND(function, arg, false, EXPECT_TRUE)
+#define EXPECT_RETURNS_FAILS(function, arg) \
+ EXPECT_HANGS_COND(function, arg, false, EXPECT_FALSE)
+#define EXPECT_HANGS_COND(function, arg, hangs, cond) do { \
+ cond(Hangs(function, arg, hangs)); \
+ if (fatal_failure[0] != '\0') { \
+ FAIL() << fatal_failure; \
+ } \
+} while (false)
+
+ struct TestMessage {
+ int16_t data; // don't really want to test empty messages
+ };
+ struct MessageArgs {
+ aos_queue *const queue;
+ int flags;
+ int16_t data; // -1 means NULL expected
+ };
+ static void WriteTestMessage(MessageArgs *args, char *failure) {
+ TestMessage *msg = reinterpret_cast<TestMessage *>(aos_queue_get_msg(args->queue));
+ if (msg == NULL) {
+ snprintf(fatal_failure, kFailureSize, "couldn't get_msg from %p", args->queue);
+ return;
+ }
+ msg->data = args->data;
+ if (aos_queue_write_msg_free(args->queue, msg, args->flags) == -1) {
+ snprintf(failure, kFailureSize, "write_msg_free(%p, %p, %d) failed",
+ args->queue, msg, args->flags);
+ }
+ }
+ static void ReadTestMessage(MessageArgs *args, char *failure) {
+ const TestMessage *msg = reinterpret_cast<const TestMessage *>(
+ aos_queue_read_msg(args->queue, args->flags));
+ if (msg == NULL) {
+ if (args->data != -1) {
+ snprintf(failure, kFailureSize, "expected data of %"PRId16" but got NULL message",
+ args->data);
+ }
+ } else {
+ if (args->data != msg->data) {
+ snprintf(failure, kFailureSize,
+ "expected data of %"PRId16" but got %"PRId16" instead",
+ args->data, msg->data);
+ }
+ aos_queue_free_msg(args->queue, msg);
+ }
+ }
+};
+char *QueueTest::fatal_failure;
+std::map<QueueTest::ChildID, QueueTest::ForkedProcess *> QueueTest::children_;
+
+TEST_F(QueueTest, Reading) {
+ static const aos_type_sig signature{sizeof(TestMessage), 1, 1};
+ aos_queue *const queue = aos_fetch_queue("Queue", &signature);
+ MessageArgs args{queue, 0, -1};
+
+ EXPECT_EQ(BLOCK, 0);
+ EXPECT_EQ(BLOCK | FROM_END, FROM_END);
+
+ args.flags = NON_BLOCK;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ args.flags = NON_BLOCK | PEEK;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ args.flags = 0;
+ EXPECT_HANGS(ReadTestMessage, &args);
+ args.flags = PEEK;
+ EXPECT_HANGS(ReadTestMessage, &args);
+ args.data = 254;
+ args.flags = BLOCK;
+ EXPECT_RETURNS(WriteTestMessage, &args);
+ args.flags = PEEK;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ args.flags = PEEK;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ args.flags = PEEK | NON_BLOCK;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ args.flags = 0;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ args.flags = 0;
+ args.data = -1;
+ EXPECT_HANGS(ReadTestMessage, &args);
+ args.flags = NON_BLOCK;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ args.flags = 0;
+ args.data = 971;
+ EXPECT_RETURNS_FAILS(ReadTestMessage, &args);
+}
+TEST_F(QueueTest, Writing) {
+ static const aos_type_sig signature{sizeof(TestMessage), 1, 1};
+ aos_queue *const queue = aos_fetch_queue("Queue", &signature);
+ MessageArgs args{queue, 0, 973};
+
+ args.flags = BLOCK;
+ EXPECT_RETURNS(WriteTestMessage, &args);
+ args.flags = BLOCK;
+ EXPECT_HANGS(WriteTestMessage, &args);
+ args.flags = NON_BLOCK;
+ EXPECT_RETURNS_FAILS(WriteTestMessage, &args);
+ args.flags = NON_BLOCK;
+ EXPECT_RETURNS_FAILS(WriteTestMessage, &args);
+ args.flags = PEEK;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ args.data = 971;
+ args.flags = OVERRIDE;
+ EXPECT_RETURNS(WriteTestMessage, &args);
+ args.flags = OVERRIDE;
+ EXPECT_RETURNS(WriteTestMessage, &args);
+ args.flags = 0;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ args.flags = NON_BLOCK;
+ EXPECT_RETURNS(WriteTestMessage, &args);
+ args.flags = 0;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ args.flags = OVERRIDE;
+ EXPECT_RETURNS(WriteTestMessage, &args);
+ args.flags = 0;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+}
+
+TEST_F(QueueTest, MultiRead) {
+ static const aos_type_sig signature{sizeof(TestMessage), 1, 1};
+ aos_queue *const queue = aos_fetch_queue("Queue", &signature);
+ MessageArgs args{queue, 0, 1323};
+
+ args.flags = BLOCK;
+ EXPECT_RETURNS(WriteTestMessage, &args);
+ args.flags = BLOCK;
+ ASSERT_TRUE(HangsFork(ReadTestMessage, &args, true, 1));
+ ASSERT_TRUE(HangsFork(ReadTestMessage, &args, true, 2));
+ EXPECT_TRUE(HangsCheck(1) != HangsCheck(2));
+ // TODO(brians) finish this
+}
+
+TEST_F(QueueTest, Recycle) {
+ // TODO(brians) basic test of recycle queue
+ // include all of the ways a message can get into the recycle queue
+ static const aos_type_sig signature{sizeof(TestMessage), 1, 2},
+ recycle_signature{sizeof(TestMessage), 2, 2};
+ aos_queue *recycle_queue = reinterpret_cast<aos_queue *>(23);
+ aos_queue *const queue = aos_fetch_queue_recycle("Queue", &signature,
+ &recycle_signature, &recycle_queue);
+ ASSERT_NE(reinterpret_cast<aos_queue *>(23), recycle_queue);
+ MessageArgs args{queue, 0, 973}, recycle{recycle_queue, 0, 973};
+
+ args.flags = BLOCK;
+ EXPECT_RETURNS(WriteTestMessage, &args);
+ EXPECT_HANGS(ReadTestMessage, &recycle);
+ args.data = 254;
+ EXPECT_RETURNS(WriteTestMessage, &args);
+ EXPECT_HANGS(ReadTestMessage, &recycle);
+ args.data = 971;
+ args.flags = OVERRIDE;
+ EXPECT_RETURNS(WriteTestMessage, &args);
+ recycle.flags = BLOCK;
+ EXPECT_RETURNS(ReadTestMessage, &recycle);
+
+ EXPECT_HANGS(ReadTestMessage, &recycle);
+
+ TestMessage *msg = static_cast<TestMessage *>(aos_queue_get_msg(queue));
+ ASSERT_TRUE(msg != NULL);
+ msg->data = 341;
+ aos_queue_free_msg(queue, msg);
+ recycle.data = 341;
+ EXPECT_RETURNS(ReadTestMessage, &recycle);
+
+ EXPECT_HANGS(ReadTestMessage, &recycle);
+
+ args.data = 254;
+ args.flags = PEEK;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ recycle.flags = BLOCK;
+ EXPECT_HANGS(ReadTestMessage, &recycle);
+ args.flags = BLOCK;
+ EXPECT_RETURNS(ReadTestMessage, &args);
+ recycle.data = 254;
+ EXPECT_RETURNS(ReadTestMessage, &recycle);
+}
+
diff --git a/aos/atom_code/ipc_lib/resource.c b/aos/atom_code/ipc_lib/resource.c
new file mode 100644
index 0000000..472191f
--- /dev/null
+++ b/aos/atom_code/ipc_lib/resource.c
@@ -0,0 +1,199 @@
+//#define TESTING_ASSERT(...)
+#define TESTING_ASSERT(cond, desc, args...) if(!(cond)){fprintf(stderr, "error: " desc " at " __FILE__ ": %d\n", ##args, __LINE__);}
+#define TESTING_ASSERT_RETURN(cond, desc, args...) TESTING_ASSERT(cond, desc, ##args); if(!(cond)){return 1;}
+// leave TESTING_ASSERT_RETURN (segfaults result otherwise)
+
+#include "resource_internal.h"
+#include <stdlib.h>
+#include <stdio.h>
+#include <sys/types.h>
+#include <unistd.h>
+#include <signal.h>
+#include <string.h>
+#include <errno.h>
+
+int RESOURCE_KILL_SIGNAL;
+
+__attribute__((constructor)) void __constructor(){
+ RESOURCE_KILL_SIGNAL = SIGRTMIN + 5;
+}
+
+void aos_resource_init(uint16_t num){
+ aos_resource *resource = aos_resource_get(num);
+ resource->num = num;
+ resource->resource_mutex = 0;
+ resource->modify = 0;
+ resource->request = 0;
+ resource->kill = 0;
+ resource->owner = 0;
+ resource->priorities = shm_malloc(sizeof(struct HeapStruct) + AOS_RESOURCE_PRIORITY_STACK_LENGTH * sizeof(uint8_t));
+ resource->priorities->Elements = (uint8_t *)((uintptr_t)resource->priorities + sizeof(struct HeapStruct)); // only do 1 shm_malloc (directly above)
+ Initialize(AOS_RESOURCE_PRIORITY_STACK_LENGTH, resource->priorities);
+ AOS_RESOURCE_STATE_SET_ON(AOS_RESOURCE_STATE_WANTS_IT, num, aos_resource_entity_root_get());
+}
+void aos_resource_entity_root_create(){
+ global_core->mem_struct->resources.root = aos_resource_entity_create(0);
+}
+inline aos_resource_entity *aos_resource_entity_root_get(){
+ return global_core->mem_struct->resources.root;
+}
+inline aos_resource *aos_resource_get(uint16_t num){
+ return &global_core->mem_struct->resources.resources[num];
+}
+
+aos_resource_entity *aos_resource_entity_create(uint8_t base_priority){
+ aos_resource_entity *local = shm_malloc(sizeof(aos_resource_entity));
+ memset(local->state, 0x00, sizeof(local->state));
+ local->base_priority = base_priority;
+ local->parent = NULL; // for the root entity
+ return local;
+}
+int aos_resource_entity_set_parent(aos_resource_entity *local, aos_resource_entity *parent){
+ TESTING_ASSERT_RETURN(local != NULL, "do not have a local entity");
+ TESTING_ASSERT_RETURN(parent != local, "can't set parent to self");
+ TESTING_ASSERT_RETURN(parent != NULL, "have to have a parent to set to");
+ local->parent = parent;
+ if(parent->parent == NULL){
+ local->root_action = getpid();
+ }else{
+ local->root_action = parent->root_action;
+ }
+ if(parent->priority > local->base_priority){
+ local->priority = parent->priority;
+ }else{
+ local->priority = local->base_priority;
+ }
+ if(local->state[0] != 0 || memcmp(local->state, local->state + 1, sizeof(local->state) - 1)){ // if it's not all 0s
+ TESTING_ASSERT(0, "local->state isn't all 0s when changing parents (fixing it)");
+ memset(local->state, 0x00, sizeof(local->state));
+ }
+ return 0;
+}
+
+void aos_resource_kill(pid_t action){
+ union sigval sival;
+ sival.sival_int = 0;
+ if(sigqueue(action, RESOURCE_KILL_SIGNAL, sival) < 0){ // if sending the signal failed
+ fprintf(stderr, "sigqueue RESOURCE_KILL_SIGNAL (which is %d) with pid %d failed with errno %d ", RESOURCE_KILL_SIGNAL, action, errno);
+ perror(NULL);
+ }
+}
+int aos_resource_request(aos_resource_entity *local, aos_resource *resource){
+ TESTING_ASSERT_RETURN(local != NULL, "do not have a local entity");
+
+ if(mutex_lock(&resource->request))
+ return 1;
+ if(mutex_lock(&resource->kill)){
+ mutex_unlock(&resource->request);
+ return 1;
+ }
+ if(mutex_lock(&resource->modify)){
+ mutex_unlock(&resource->kill);
+ mutex_unlock(&resource->request);
+ return 1;
+ }
+
+ aos_resource_entity *c = local;
+ while(c->parent != NULL && !AOS_RESOURCE_STATE_GET_HAS_IT(resource->num, c)){
+ c = c->parent;
+ }
+ TESTING_ASSERT((c->parent == NULL) == (c == aos_resource_entity_root_get()), "found a resource with no parent that isn't the root")
+ if(c->parent == NULL && !AOS_RESOURCE_STATE_GET_WANTS_IT(resource->num, c)){ // if c is the root entity and doesn't want it
+ TESTING_ASSERT(0, "root entity does not want resource %d (will fix it)", resource->num);
+ *((int *)NULL) = 0;
+ AOS_RESOURCE_STATE_SET_ON(AOS_RESOURCE_STATE_WANTS_IT, resource->num, c);
+ }
+ uint8_t locked_resource_mutex = 0;
+ if(AOS_RESOURCE_STATE_GET_HAS_PASSED_DOWN(resource->num, c)){
+ if(c->parent == NULL){
+ if(GetMin(resource->priorities) >= local->priority){
+ mutex_unlock(&resource->modify);
+ aos_resource_kill(resource->owner);
+ if(mutex_lock(&resource->kill)){ // got released by one that got killed (after unlocking resource_mutex)
+ mutex_unlock(&resource->resource_mutex);
+ mutex_unlock(&resource->request);
+ return 1;
+ }
+ if(mutex_lock(&resource->resource_mutex)){ // wait for the other process to release it
+ mutex_unlock(&resource->request);
+ return 1;
+ }
+ locked_resource_mutex = 1;
+ if(mutex_lock(&resource->modify)){
+ mutex_unlock(&resource->request);
+ return 1;
+ }
+ }else{
+ mutex_unlock(&resource->modify);
+ mutex_unlock(&resource->request);
+ return -1;
+ }
+ }else{
+ fprintf(stderr, "PROGRAMMER ERROR!!!!! 2 sub-actions both requested resource %d!!! stopping the root action\n", resource->num);
+ mutex_unlock(&resource->modify);
+ mutex_unlock(&resource->request);
+ return -1;
+ }
+ }
+ AOS_RESOURCE_STATE_SET_ON(AOS_RESOURCE_STATE_WANTS_IT, resource->num, local);
+ aos_resource_entity *c2 = local;
+ do{
+ c2 = c2->parent;
+ TESTING_ASSERT_RETURN(c2 != NULL, "couldn't find the parent that has resource %d", resource->num)
+ AOS_RESOURCE_STATE_SET_ON(AOS_RESOURCE_STATE_HAS_PASSED_DOWN, resource->num, c2);
+ } while(c2 != c);
+ TESTING_ASSERT(c2 == c, "c2 != c");
+ if(c->parent == NULL){ // if you found the root entity
+ resource->owner = local->root_action;
+ if(!locked_resource_mutex){
+ int rv = mutex_trylock(&resource->resource_mutex); // don't deadlock if somebody died or whatever
+ TESTING_ASSERT(rv == 0, "the resource_mutex was already locked when getting %d from the root", resource->num);
+ }
+ }else{
+ TESTING_ASSERT(resource->owner == local->root_action, "my action chain has resource %d, but my chain's root(%d) isn't the owner(%d)", resource->num, local->root_action, resource->owner);
+ TESTING_ASSERT(mutex_trylock(&resource->resource_mutex) != 0, "my action has the resource_mutex for %d, but the resource_mutex wasn't already locked", resource->num);
+ }
+ if(Insert(local->priority, resource->priorities) < 0){
+ fprintf(stderr, "BAD NEWS: ran out of space on the priority heap for resource %d. Increase the size of AOS_RESOURCE_PRIORITY_STACK_LENGTH in resource.h\n", resource->num);
+ mutex_unlock(&resource->modify);
+ mutex_unlock(&resource->request);
+ return -1;
+ }
+ mutex_unlock(&resource->modify);
+ mutex_unlock(&resource->kill);
+ mutex_unlock(&resource->request);
+ return 0;
+}
+
+int aos_resource_release(aos_resource_entity *local, aos_resource *resource){
+ TESTING_ASSERT_RETURN(local != NULL, "do not have a local entity");
+
+ if(mutex_lock(&resource->modify)){
+ return 1;
+ }
+
+ AOS_RESOURCE_STATE_SET_OFF(AOS_RESOURCE_STATE_WANTS_IT, resource->num, local);
+ if(!AOS_RESOURCE_STATE_GET_HAS_PASSED_DOWN(resource->num, local)){ // if we're actually supposed to go release it
+ aos_resource_entity *c = local;
+ while(c->parent != NULL && !AOS_RESOURCE_STATE_GET_WANTS_IT(resource->num, c)){
+ AOS_RESOURCE_STATE_SET_OFF(AOS_RESOURCE_STATE_HAS_PASSED_DOWN, resource->num, c);
+ c = c->parent;
+ }
+ if(c->parent == NULL && !AOS_RESOURCE_STATE_GET_WANTS_IT(resource->num, c)){ // if c is the root entity and doesn't want it
+ TESTING_ASSERT(0, "root entity does not want resource %d (will fix it)", resource->num);
+ AOS_RESOURCE_STATE_SET_ON(AOS_RESOURCE_STATE_WANTS_IT, resource->num, c);
+ }
+ AOS_RESOURCE_STATE_SET_OFF(AOS_RESOURCE_STATE_HAS_PASSED_DOWN, resource->num, c);
+ Remove(local->priority, resource->priorities);
+ TESTING_ASSERT(local->root_action == resource->owner, "freeing a resource (%d) whose owner(%d) isn't my chain's root(%d)", resource->num, resource->owner, local->root_action);
+ if(c->parent == NULL){ // if you gave it back to the root entity (c)
+ TESTING_ASSERT(IsEmpty(resource->priorities), "priority stack isn't empty (size=%d)", GetSize(resource->priorities));
+ resource->owner = 0;
+ mutex_unlock(&resource->resource_mutex);
+ mutex_unlock(&resource->kill);
+ }
+ } // else has passed it down
+ mutex_unlock(&resource->modify);
+ return 0;
+}
+
diff --git a/aos/atom_code/ipc_lib/resource.h b/aos/atom_code/ipc_lib/resource.h
new file mode 100644
index 0000000..de1de1a
--- /dev/null
+++ b/aos/atom_code/ipc_lib/resource.h
@@ -0,0 +1,28 @@
+#ifndef __AOS_RESOURCE_H_
+#define __AOS_RESOURCE_H_
+
+// notes at <https://docs.google.com/document/d/1gzRrVcqL2X9VgNQUI5DrvLVVVziIH7c5ZerATVbiS7U/edit?hl=en_US>
+
+#include <sys/types.h>
+#include "shared_mem.h"
+#include "binheap.h"
+#include "aos_sync.h"
+#include "core_lib.h"
+
+#define AOS_RESOURCE_PRIORITY_STACK_LENGTH 50
+
+extern int RESOURCE_KILL_SIGNAL;
+
+/* Return Values
+ 0 = success
+ -1 = you should stop (like if you got killed) (only for request)
+ 1 = error
+*/
+int aos_resource_request(aos_resource_entity *local, aos_resource *resource);
+int aos_resource_release(aos_resource_entity *local, aos_resource *resource);
+int aos_resource_entity_set_parent(aos_resource_entity *local, aos_resource_entity *parent);
+aos_resource_entity *aos_resource_entity_create(uint8_t base_priority);
+aos_resource *aos_resource_get(uint16_t num);
+aos_resource_entity *aos_resource_entity_root_get(void);
+
+#endif
diff --git a/aos/atom_code/ipc_lib/resource_core.h b/aos/atom_code/ipc_lib/resource_core.h
new file mode 100644
index 0000000..27d1af8
--- /dev/null
+++ b/aos/atom_code/ipc_lib/resource_core.h
@@ -0,0 +1,28 @@
+#ifndef AOS_ATOM_CODE_IPC_LIB_RESOURCE_CORE_H_
+#define AOS_ATOM_CODE_IPC_LIB_RESOURCE_CORE_H_
+// this file has to be separate due to #include order dependencies
+
+#include "aos/atom_code/ipc_lib/shared_mem.h"
+#include "aos/atom_code/ipc_lib/binheap.h"
+#include "aos/ResourceList.h"
+
+typedef struct aos_resource_t{
+ mutex resource_mutex; // gets locked whenever resource is taken from root entity and unlocked when its given back
+ mutex modify; // needs to be locked while somebody is requesting or releasing this resource
+ mutex request; // needs to be locked while somebody is requesting this resource (including possibly waiting for somebody else to release it after being killed)
+ mutex kill; // gets locked while somebody is dying for this resource (gets unlocked whenever this resource gets given back to the root entity)
+ pid_t owner;
+ PriorityQueue priorities; // lower number = higher priority
+
+ uint16_t num;
+} aos_resource;
+typedef struct aos_resource_entity_t aos_resource_entity;
+typedef struct aos_resource_list_t {
+ aos_resource resources[AOS_RESOURCE_NUM];
+ aos_resource_entity *root;
+} aos_resource_list;
+void aos_resource_init(uint16_t num);
+void aos_resource_entity_root_create(void);
+
+#endif
+
diff --git a/aos/atom_code/ipc_lib/resource_internal.h b/aos/atom_code/ipc_lib/resource_internal.h
new file mode 100644
index 0000000..eebecf9
--- /dev/null
+++ b/aos/atom_code/ipc_lib/resource_internal.h
@@ -0,0 +1,27 @@
+#ifndef __AOS_RESOURCE_INTERNAL_H_
+#define __AOS_RESOURCE_INTERNAL_H_
+
+#include "resource.h"
+
+#define AOS_RESOURCE_STATES_PER_BYTE 4
+#define AOS_RESOURCE_STATE_SHIFTER(num) ((num % AOS_RESOURCE_STATES_PER_BYTE) * (8 / AOS_RESOURCE_STATES_PER_BYTE))
+#define AOS_RESOURCE_STATE_GET(num, entity) (entity->state[num / AOS_RESOURCE_STATES_PER_BYTE] >> AOS_RESOURCE_STATE_SHIFTER(num))
+#define AOS_RESOURCE_STATE_SET_ON(mask, num, entity) (entity->state[num / AOS_RESOURCE_STATES_PER_BYTE] |= (mask << AOS_RESOURCE_STATE_SHIFTER(num)))
+#define AOS_RESOURCE_STATE_SET_OFF(mask, num, entity) (entity->state[num / AOS_RESOURCE_STATES_PER_BYTE] &= ~(mask << AOS_RESOURCE_STATE_SHIFTER(num)))
+#define AOS_RESOURCE_STATE_GET_HAS_IT(num, entity) (AOS_RESOURCE_STATE_GET_WANTS_IT(num, entity) || AOS_RESOURCE_STATE_GET_HAS_PASSED_DOWN(num, entity))
+#define AOS_RESOURCE_STATE_WANTS_IT 0x01
+#define AOS_RESOURCE_STATE_HAS_PASSED_DOWN 0x02
+#define AOS_RESOURCE_STATE_GET_WANTS_IT(num, entity) (AOS_RESOURCE_STATE_GET(num, entity) & AOS_RESOURCE_STATE_WANTS_IT)
+#define AOS_RESOURCE_STATE_GET_HAS_PASSED_DOWN(num, entity) (AOS_RESOURCE_STATE_GET(num, entity) & AOS_RESOURCE_STATE_HAS_PASSED_DOWN)
+
+struct aos_resource_entity_t{
+ aos_resource_entity *parent;
+ uint8_t state[(AOS_RESOURCE_NUM + (AOS_RESOURCE_STATES_PER_BYTE - 1)) / AOS_RESOURCE_STATES_PER_BYTE];
+ pid_t root_action;
+ uint8_t base_priority, priority;
+};
+
+inline void aos_resource_init(uint16_t num);
+
+#endif
+
diff --git a/aos/atom_code/ipc_lib/resource_list.txt b/aos/atom_code/ipc_lib/resource_list.txt
new file mode 100644
index 0000000..1aabdca
--- /dev/null
+++ b/aos/atom_code/ipc_lib/resource_list.txt
@@ -0,0 +1,4 @@
+test_resource1
+test_resource2
+drivetrain_left
+drivetrain_right
diff --git a/aos/atom_code/ipc_lib/resource_test.cpp b/aos/atom_code/ipc_lib/resource_test.cpp
new file mode 100644
index 0000000..9ce6e06
--- /dev/null
+++ b/aos/atom_code/ipc_lib/resource_test.cpp
@@ -0,0 +1,28 @@
+#include "aos/atom_code/ipc_lib/sharedmem_test_setup.h"
+#include "aos/aos_core.h"
+
+#include <gtest/gtest.h>
+#include <gtest/gtest-spi.h>
+
+class ResourceTest : public SharedMemTestSetup{
+};
+
+TEST_F(ResourceTest, GetResource){
+ aos_resource *first = aos_resource_get(1);
+ AllSharedMemAllocated();
+ aos_resource *second = aos_resource_get(1);
+ EXPECT_EQ(first, second);
+}
+TEST_F(ResourceTest, CheckLocal){
+ EXPECT_EQ(1, aos_resource_request(NULL, aos_resource_get(2)));
+}
+
+TEST_F(ResourceTest, LocalCreate){
+ EXPECT_TRUE(aos_resource_entity_create(56) != NULL);
+}
+TEST_F(ResourceTest, LocalSetParentSelf){
+ aos_resource_entity *local = aos_resource_entity_create(76);
+ ASSERT_TRUE(local != NULL);
+ EXPECT_EQ(1, aos_resource_entity_set_parent(local, local));
+}
+
diff --git a/aos/atom_code/ipc_lib/shared_mem.c b/aos/atom_code/ipc_lib/shared_mem.c
new file mode 100644
index 0000000..f631b78
--- /dev/null
+++ b/aos/atom_code/ipc_lib/shared_mem.c
@@ -0,0 +1,119 @@
+#include "shared_mem.h"
+
+#include <stdio.h>
+#include <string.h>
+#include <sys/mman.h>
+#include <fcntl.h>
+#include <unistd.h>
+#include <sys/types.h>
+#include <errno.h>
+
+// the path for the shared memory segment. see shm_open(3) for restrictions
+#define AOS_SHM_NAME "/aos_shared_mem"
+// Size of the shared mem segment.
+// set to the maximum number that worked
+#define SIZEOFSHMSEG (4096 * 27813)
+
+ptrdiff_t aos_core_get_mem_usage(void) {
+ return global_core->size -
+ ((ptrdiff_t)global_core->mem_struct->msg_alloc -
+ (ptrdiff_t)global_core->mem_struct);
+}
+
+struct aos_core global_core_data;
+struct aos_core *global_core = NULL;
+
+int aos_core_create_shared_mem(enum aos_core_create to_create) {
+ global_core = &global_core_data;
+ int shm;
+before:
+ if (to_create == create) {
+ printf("shared_mem: creating\n");
+ shm = shm_open(AOS_SHM_NAME, O_RDWR | O_CREAT | O_EXCL, 0666);
+ global_core->owner = 1;
+ if (shm == -1 && errno == EEXIST) {
+ printf("shared_mem: going to shm_unlink(" AOS_SHM_NAME ")\n");
+ if (shm_unlink(AOS_SHM_NAME) == -1) {
+ fprintf(stderr, "shared_mem: shm_unlink(" AOS_SHM_NAME ") failed with of %d: %s\n", errno, strerror(errno));
+ } else {
+ goto before;
+ }
+ }
+ } else {
+ printf("shared_mem: not creating\n");
+ shm = shm_open(AOS_SHM_NAME, O_RDWR, 0);
+ global_core->owner = 0;
+ }
+ if (shm == -1) {
+ fprintf(stderr, "shared_mem:"
+ " shm_open(" AOS_SHM_NAME ", O_RDWR [| O_CREAT | O_EXCL, 0|0666)"
+ " failed with %d: %s\n", errno, strerror(errno));
+ return -1;
+ }
+ if (global_core->owner) {
+ if (ftruncate(shm, SIZEOFSHMSEG) == -1) {
+ fprintf(stderr, "shared_mem: fruncate(%d, 0x%zx) failed with %d: %s\n",
+ shm, (size_t)SIZEOFSHMSEG, errno, strerror(errno));
+ return -1;
+ }
+ }
+ void *shm_address = mmap(
+ (void *)SHM_START, SIZEOFSHMSEG, PROT_READ | PROT_WRITE,
+ MAP_SHARED | MAP_FIXED | MAP_LOCKED | MAP_POPULATE, shm, 0);
+ if (shm_address == MAP_FAILED) {
+ fprintf(stderr, "shared_mem: mmap(%p, 0x%zx, stuff, stuff, %d, 0) failed"
+ " with %d: %s\n",
+ (void *)SHM_START, SIZEOFSHMSEG, shm, errno, strerror(errno));
+ return -1;
+ }
+ printf("shared_mem: shm at: %p\n", shm_address);
+ if (close(shm) == -1) {
+ printf("shared_mem: close(%d(=shm) failed with %d: %s\n",
+ shm, errno, strerror(errno));
+ }
+ if (shm_address != (void *)SHM_START) {
+ fprintf(stderr, "shared_mem: shm isn't at hard-coded %p. at %p instead\n",
+ (void *)SHM_START, shm_address);
+ return -1;
+ }
+ return aos_core_use_address_as_shared_mem(shm_address, SIZEOFSHMSEG);
+}
+
+int aos_core_use_address_as_shared_mem(void *address, size_t size) {
+ global_core->mem_struct = address;
+ global_core->size = size;
+ global_core->shared_mem = (uint8_t *)address + sizeof(*global_core->mem_struct);
+ if (global_core->owner) {
+ global_core->mem_struct->msg_alloc = (uint8_t *)address + global_core->size;
+ init_shared_mem_core(global_core->mem_struct);
+ }
+ if (global_core->owner) {
+ condition_set(&global_core->mem_struct->creation_condition);
+ } else {
+ if (condition_wait(&global_core->mem_struct->creation_condition) != 0) {
+ fprintf(stderr, "waiting on creation_condition failed\n");
+ return -1;
+ }
+ }
+ fprintf(stderr, "shared_mem: end of create_shared_mem owner=%d\n",
+ global_core->owner);
+ return 0;
+}
+
+int aos_core_free_shared_mem(){
+ void *shm_address = global_core->shared_mem;
+ if (munmap((void *)SHM_START, SIZEOFSHMSEG) == -1) {
+ fprintf(stderr, "shared_mem: munmap(%p, 0x%zx) failed with %d: %s\n",
+ shm_address, SIZEOFSHMSEG, errno, strerror(errno));
+ return -1;
+ }
+ if (global_core->owner) {
+ if (shm_unlink(AOS_SHM_NAME)) {
+ fprintf(stderr, "shared_mem: shm_unlink(" AOS_SHM_NAME ") failed with %d: %s\n",
+ errno, strerror(errno));
+ return -1;
+ }
+ }
+ return 0;
+}
+
diff --git a/aos/atom_code/ipc_lib/shared_mem.h b/aos/atom_code/ipc_lib/shared_mem.h
new file mode 100644
index 0000000..b1a2608
--- /dev/null
+++ b/aos/atom_code/ipc_lib/shared_mem.h
@@ -0,0 +1,46 @@
+#ifndef _SHARED_MEM_H_
+#define _SHARED_MEM_H_
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include "core_lib.h"
+#include <stddef.h>
+#include <unistd.h>
+
+// Where the shared memory segment starts in each process's address space.
+// Has to be the same in all of them so that stuff in shared memory
+// can have regular pointers to other stuff in shared memory.
+#define SHM_START 0x20000000
+
+enum aos_core_create {
+ create,
+ reference
+};
+struct aos_core {
+ int owner;
+ void *shared_mem;
+ // How large the chunk of shared memory is.
+ ptrdiff_t size;
+ aos_shm_core *mem_struct;
+};
+
+ptrdiff_t aos_core_get_mem_usage(void);
+
+// Takes the specified memory address and uses it as the shared memory.
+// address is the memory address, and size is the size of the memory.
+// global_core needs to point to an instance of struct aos_core, and owner
+// should be set correctly there.
+// The owner should verify that the first sizeof(mutex) of data is set to 0
+// before passing the memory to this function.
+int aos_core_use_address_as_shared_mem(void *address, size_t size);
+
+int aos_core_create_shared_mem(enum aos_core_create to_create);
+int aos_core_free_shared_mem(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/aos/atom_code/ipc_lib/sharedmem_test_setup.h b/aos/atom_code/ipc_lib/sharedmem_test_setup.h
new file mode 100644
index 0000000..e461c43
--- /dev/null
+++ b/aos/atom_code/ipc_lib/sharedmem_test_setup.h
@@ -0,0 +1,147 @@
+// defines a fixture (SharedMemTestSetup) that sets up shared memory
+
+extern "C" {
+#include "shared_mem.h"
+ extern struct aos_core *global_core;
+}
+
+#include <signal.h>
+
+#include <gtest/gtest.h>
+#include <sys/types.h>
+
+// TODO(brians) read logs from here
+class SharedMemTestSetup : public testing::Test{
+ protected:
+ pid_t core;
+ int start[2];
+ int memcheck[2];
+ static void signal_handler(int){
+ if(aos_core_free_shared_mem()){
+ exit(- 1);
+ }
+ exit(0);
+ }
+ static int get_mem_usage(){
+ return global_core->size - ((uint8_t *)global_core->mem_struct->msg_alloc - (uint8_t *)SHM_START);
+ }
+ bool checking_mem;
+
+ virtual void BeforeLocalShmSetup() {}
+ virtual void SetUp(){
+ ASSERT_EQ(0, pipe(start)) << "couldn't create start pipes";
+ ASSERT_EQ(0, pipe(memcheck)) << "couldn't create memcheck pipes";
+ checking_mem = false;
+ if((core = fork()) == 0){
+ close(start[0]);
+ close(memcheck[1]);
+ struct sigaction act;
+ act.sa_handler = signal_handler;
+ sigaction(SIGINT, &act, NULL);
+ if(aos_core_create_shared_mem(create)){
+ exit(-1);
+ }
+ write_pipe(start[1], "a", 1);
+ int usage = 0;
+ while(1){
+ char buf1;
+ read_pipe(memcheck[0], &buf1, 1);
+ if(usage == 0)
+ usage = get_mem_usage();
+ if(usage == get_mem_usage())
+ buf1 = 1;
+ else
+ buf1 = 0;
+ write_pipe(start[1], &buf1, 1);
+ }
+ }
+ close(start[1]);
+ close(memcheck[0]);
+ ASSERT_NE(-1, core) << "fork failed";
+ char buf;
+ read_pipe(start[0], &buf, 1);
+
+ BeforeLocalShmSetup();
+
+ ASSERT_EQ(0, aos_core_create_shared_mem(reference)) << "couldn't create shared mem reference";
+ }
+ virtual void TearDown(){
+ if(checking_mem){
+ write_pipe(memcheck[1], "a", 1);
+ char buf;
+ read_pipe(start[0], &buf, 1);
+ EXPECT_EQ(1, buf) << "memory got leaked";
+ }
+ EXPECT_EQ(0, aos_core_free_shared_mem()) << "issues freeing shared mem";
+ if(core > 0){
+ kill(core, SIGINT);
+ siginfo_t status;
+ ASSERT_EQ(0, waitid(P_PID, core, &status, WEXITED)) << "waiting for the core to finish failed";
+ EXPECT_EQ(CLD_EXITED, status.si_code) << "core died";
+ EXPECT_EQ(0, status.si_status) << "core exited with an error";
+ }
+ }
+ // if any more shared memory gets allocated after calling this and not freed by the end, it's an error
+ void AllSharedMemAllocated(){
+ checking_mem = true;
+ write_pipe(memcheck[1], "a", 1);
+ char buf;
+ read_pipe(start[0], &buf, 1);
+ }
+ private:
+ // Wrapper functions for pipes because they should never have errors.
+ void read_pipe(int fd, void *buf, size_t count) {
+ if (read(fd, buf, count) < 0) abort();
+ }
+ void write_pipe(int fd, const void *buf, size_t count) {
+ if (write(fd, buf, count) < 0) abort();
+ }
+};
+class ExecVeTestSetup : public SharedMemTestSetup {
+ protected:
+ std::vector<std::string> files;
+ std::vector<pid_t> pids;
+ virtual void BeforeLocalShmSetup(){
+ std::vector<std::string>::iterator it;
+ pid_t child;
+ for(it = files.begin(); it < files.end(); ++it){
+ if((child = fork()) == 0){
+ char *null = NULL;
+ execve(it->c_str(), &null, &null);
+ ADD_FAILURE() << "execve failed";
+ perror("execve");
+ exit(0);
+ }
+ if(child > 0)
+ pids.push_back(child);
+ else
+ ADD_FAILURE() << "fork failed return=" << child;
+ }
+ usleep(150000);
+ }
+ virtual void TearDown(){
+ std::vector<pid_t>::iterator it;
+ siginfo_t status;
+ for(it = pids.begin(); it < pids.end(); ++it){
+ printf("attempting to SIGINT(%d) %d\n", SIGINT, *it);
+ if(*it > 0){
+ kill(*it, SIGINT);
+ ASSERT_EQ(0, waitid(P_PID, *it, &status, WEXITED)) << "waiting for the AsyncAction(pid=" << *it << ") to finish failed";
+ EXPECT_EQ(CLD_EXITED, status.si_code) << "child died (killed by signal is " << (int)CLD_KILLED << ")";
+ EXPECT_EQ(0, status.si_status) << "child exited with an error";
+ }else{
+ FAIL();
+ }
+ }
+
+ SharedMemTestSetup::TearDown();
+ }
+ // call this _before_ ExecVeTestSetup::SetUp()
+ void AddProcess(const std::string file){
+ files.push_back(file);
+ }
+ void PercolatePause(){
+ usleep(50000);
+ }
+};
+
diff --git a/aos/atom_code/logging/atom_logging.cpp b/aos/atom_code/logging/atom_logging.cpp
new file mode 100644
index 0000000..e98078b
--- /dev/null
+++ b/aos/atom_code/logging/atom_logging.cpp
@@ -0,0 +1,259 @@
+#include <stdarg.h>
+#include <stdio.h>
+#include <string.h>
+#include <time.h>
+#include <sys/types.h>
+#include <errno.h>
+#include <unistd.h>
+#include <limits.h>
+
+#include <algorithm>
+
+#include "aos/aos_core.h"
+#include "aos/common/die.h"
+
+#define DECL_LEVEL(name, value) const log_level name = value;
+DECL_LEVELS
+#undef DECL_LEVEL
+
+log_level log_min = 0;
+
+static const aos_type_sig message_sig = {sizeof(log_queue_message), 1234, 1500};
+static const char *name;
+static size_t name_size;
+static aos_queue *queue;
+static log_message corked_message;
+static int cork_line_min, cork_line_max;
+bool log_initted = false;
+
+static inline void cork_init() {
+ corked_message.message[0] = '\0'; // make strlen of it 0
+ cork_line_min = INT_MAX;
+ cork_line_max = -1;
+}
+int log_init(const char *name_in){
+ if (log_initted) {
+ return 1;
+ }
+
+ const size_t name_in_len = strlen(name_in);
+ const char *last_slash = static_cast<const char *>(memrchr(name_in,
+ '/', name_in_len));
+ if (last_slash == NULL) {
+ name_size = name_in_len;
+ last_slash = name_in - 1;
+ } else {
+ name_size = name_in + name_in_len - last_slash;
+ }
+ if (name_size >= sizeof(log_message::name)) {
+ fprintf(stderr, "logging: error: name '%s' (going to use %zu bytes) is too long\n",
+ name_in, name_size);
+ return -1;
+ }
+ char *const tmp = static_cast<char *>(malloc(name_size + 1));
+ if (tmp == NULL) {
+ fprintf(stderr, "logging: error: couldn't malloc(%zd)\n", name_size + 1);
+ return -1;
+ }
+ name = tmp;
+ memcpy(tmp, last_slash + 1, name_size);
+ tmp[name_size] = 0;
+ queue = aos_fetch_queue("LoggingQueue", &message_sig);
+ if (queue == NULL) {
+ fprintf(stderr, "logging: error: couldn't fetch queue\n");
+ return -1;
+ }
+
+ cork_init();
+
+ log_initted = true;
+ return 0;
+}
+void log_uninit() {
+ free(const_cast<char *>(name));
+ name = NULL;
+ name_size = 0;
+ queue = NULL;
+ log_initted = false;
+}
+
+static inline void check_init() {
+ if (!log_initted) {
+ fprintf(stderr, "logging: warning: not initialized in %jd."
+ " initializing using \"<null>\" as name\n", static_cast<intmax_t>(getpid()));
+ log_init("<null>");
+ }
+}
+
+const log_message *log_read_next2(int flags, int *index) {
+ check_init();
+ return static_cast<const log_message *>(aos_queue_read_msg_index(queue, flags, index));
+}
+const log_message *log_read_next1(int flags) {
+ check_init();
+ const log_message *r = NULL;
+ do {
+ r = static_cast<const log_message *>(aos_queue_read_msg(queue, flags));
+ } while ((flags & BLOCK) && r == NULL); // not blocking means return a NULL if that's what it gets
+ return r;
+}
+void log_free_message(const log_message *msg) {
+ check_init();
+ aos_queue_free_msg(queue, msg);
+}
+
+int log_crio_message_send(log_crio_message &to_send) {
+ check_init();
+
+ log_crio_message *msg = static_cast<log_crio_message *>(aos_queue_get_msg(queue));
+ if (msg == NULL) {
+ fprintf(stderr, "logging: error: couldn't get a message to send '%s'\n",
+ to_send.message);
+ return -1;
+ }
+ //*msg = to_send;
+ static_assert(sizeof(to_send) == sizeof(*msg), "something is very wrong here");
+ memcpy(msg, &to_send, sizeof(to_send));
+ if (aos_queue_write_msg(queue, msg, OVERRIDE) < 0) {
+ fprintf(stderr, "logging: error: writing crio message '%s' failed\n", msg->message);
+ aos_queue_free_msg(queue, msg);
+ return -1;
+ }
+
+ return 0;
+}
+
+// Prints format (with ap) into output and correctly deals with the message
+// being too long etc.
+// Returns whether it succeeded or not.
+static inline bool vsprintf_in(char *output, size_t output_size,
+ const char *format, va_list ap) {
+ static const char *continued = "...\n";
+ const size_t size = output_size - strlen(continued);
+ const int ret = vsnprintf(output, size, format, ap);
+ if (ret < 0) {
+ fprintf(stderr, "logging: error: vsnprintf failed with %d (%s)\n",
+ errno, strerror(errno));
+ return false;
+ } else if (static_cast<uintmax_t>(ret) >= static_cast<uintmax_t>(size)) {
+ // overwrite the NULL at the end of the existing one and
+ // copy in the one on the end of continued
+ memcpy(&output[size - 1], continued, strlen(continued) + 1);
+ }
+ return true;
+}
+static inline bool write_message(log_message *msg, log_level level) {
+ msg->level = level;
+ msg->source = getpid();
+ memcpy(msg->name, name, name_size + 1);
+ if (clock_gettime(CLOCK_REALTIME, &msg->time) == -1) {
+ fprintf(stderr, "logging: warning: couldn't get the current time "
+ "because of %d (%s)\n", errno, strerror(errno));
+ msg->time.tv_sec = 0;
+ msg->time.tv_nsec = 0;
+ }
+
+ static uint8_t local_sequence = -1;
+ msg->sequence = ++local_sequence;
+
+ if (aos_queue_write_msg(queue, msg, OVERRIDE) < 0) {
+ fprintf(stderr, "logging: error: writing message '%s' failed\n", msg->message);
+ aos_queue_free_msg(queue, msg);
+ return false;
+ }
+ return true;
+}
+static inline int vlog_do(log_level level, const char *format, va_list ap) {
+ log_message *msg = static_cast<log_message *>(aos_queue_get_msg(queue));
+ if (msg == NULL) {
+ fprintf(stderr, "logging: error: couldn't get a message to send '%s'\n", format);
+ return -1;
+ }
+
+ if (!vsprintf_in(msg->message, sizeof(msg->message), format, ap)) {
+ return -1;
+ }
+
+ if (!write_message(msg, level)) {
+ return -1;
+ }
+
+ if (level == FATAL) {
+ aos::Die("%s", msg->message);
+ }
+
+ return 0;
+}
+int log_do(log_level level, const char *format, ...) {
+ check_init();
+ va_list ap;
+ va_start(ap, format);
+ const int ret = vlog_do(level, format, ap);
+ va_end(ap);
+ return ret;
+}
+
+static inline int vlog_cork(int line, const char *format, va_list ap) {
+ const size_t message_length = strlen(corked_message.message);
+ if (line > cork_line_max) cork_line_max = line;
+ if (line < cork_line_min) cork_line_min = line;
+ return vsprintf_in(corked_message.message + message_length,
+ sizeof(corked_message.message) - message_length, format, ap) ? 0 : -1;
+}
+int log_cork(int line, const char *format, ...) {
+ check_init();
+ va_list ap;
+ va_start(ap, format);
+ const int ret = vlog_cork(line, format, ap);
+ va_end(ap);
+ return ret;
+}
+static inline bool log_uncork_helper(char *output, size_t output_size,
+ const char *format, ...) {
+ check_init();
+ va_list ap;
+ va_start(ap, format);
+ const bool ret = vsprintf_in(output, output_size, format, ap);
+ va_end(ap);
+ return ret;
+}
+int log_uncork(int line, log_level level, const char *begin_format,
+ const char *format, ...) {
+ check_init();
+ va_list ap;
+ va_start(ap, format);
+ const int ret = vlog_cork(line, format, ap);
+ va_end(ap);
+ if (ret != 0) {
+ return ret;
+ }
+
+ log_message *msg = static_cast<log_message *>(aos_queue_get_msg(queue));
+ if (msg == NULL) {
+ fprintf(stderr, "logging: error: couldn't get a message to send '%s'\n", format);
+ cork_init();
+ return -1;
+ }
+
+ static char new_format[LOG_MESSAGE_LEN];
+ if (!log_uncork_helper(new_format, sizeof(new_format), begin_format,
+ cork_line_min, cork_line_max)) {
+ cork_init();
+ return -1;
+ }
+ const size_t new_length = strlen(new_format);
+ memcpy(msg->message, new_format, new_length);
+ memcpy(msg->message + new_length, corked_message.message,
+ std::min(strlen(corked_message.message) + 1,
+ sizeof(msg->message) - new_length));
+ // in case corked_message.message was too long, it'll still be NULL-terminated
+ msg->message[sizeof(msg->message) - 1] = '\0';
+ cork_init();
+
+ if (!write_message(msg, level)) {
+ return -1;
+ }
+
+ return 0;
+}
+
diff --git a/aos/atom_code/logging/atom_logging.h b/aos/atom_code/logging/atom_logging.h
new file mode 100644
index 0000000..6211e22
--- /dev/null
+++ b/aos/atom_code/logging/atom_logging.h
@@ -0,0 +1,109 @@
+#ifndef AOS_ATOM_CODE_LOGGING_LOGGING_H_
+#define AOS_ATOM_CODE_LOGGING_LOGGING_H_
+
+// IWYU pragma: private, include "aos/common/logging/logging.h"
+
+#ifndef AOS_COMMON_LOGGING_LOGGING_H_
+#error This file may only be #included through common/logging/logging.h!!!
+#endif
+
+#include "aos/aos_core.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+int log_init(const char *name);
+// WARNING: THIS LEAKS MEMORY AND SHARED MEMORY
+void log_uninit(void);
+
+extern log_level log_min;
+
+// The basic structure that goes into the shared memory queue.
+// It is packed so the pid_t at the front is at the same location as
+// the one in log_crio_message.
+typedef struct log_message_t_ {
+ pid_t source;
+ log_level level;
+ char message[LOG_MESSAGE_LEN];
+ char name[40];
+ struct timespec time;
+ uint8_t sequence; // per process
+} __attribute__((packed)) log_message;
+
+#ifdef __cplusplus
+#define LOG_BOOL bool
+#else
+#define LOG_BOOL uint8_t
+#endif
+extern LOG_BOOL log_initted;
+#undef LOG_BOOL
+
+// Unless explicitly stated otherwise, format must always be a string constant
+// and args are printf-style arguments for format.
+// The validitiy of format and args together will be checked at compile time
+// using a gcc function attribute.
+
+// Logs the specified thing.
+#define LOG(level, format, args...) do { \
+ if (level >= log_min) { \
+ log_do(level, LOG_SOURCENAME ": " STRINGIFY(__LINE__) ": " format, ##args); \
+ } \
+} while (0)
+// Allows "bottling up" multiple log fragments which can then all be logged in
+// one message with LOG_UNCORK.
+// format does not have to be a constant
+#define LOG_CORK(format, args...) do { \
+ log_cork(__LINE__, format, ##args); \
+} while (0)
+// Actually logs all of the saved up log fragments (including format and args on
+// the end).
+#define LOG_UNCORK(level, format, args...) do { \
+ log_uncork(__LINE__, level, LOG_SOURCENAME ": %d-%d: ", format, ##args); \
+} while (0)
+// Makes a normal logging call if possible or just prints it out on stderr.
+#define LOG_IFINIT(level, format, args...) do{ \
+ if(log_initted) { \
+ LOG(level, format, args); \
+ } else { \
+ fprintf(stderr, "%s-noinit: " format, log_str(level), ##args); \
+ } \
+}while(0)
+
+// All functions return 0 for success and - for error.
+
+// Actually implements the basic logging call.
+// Does not check that level is valid.
+// TODO(brians): Fix this so it works with clang.
+int log_do(log_level level, const char *format, ...)
+ __attribute__((format(gnu_printf, 2, 3)));
+
+// TODO(brians): Fix this so it works with clang.
+int log_cork(int line, const char *format, ...)
+ __attribute__((format(gnu_printf, 2, 3)));
+// Implements the uncork logging call.
+// IMPORTANT: begin_format must have 2 %d formats as its only 2 format specifiers
+// which will get passed the minimum and maximum line numbers that have been
+// corked into this call.
+// TODO(brians): Fix this so it works with clang.
+int log_uncork(int line, log_level level, const char *begin_format,
+ const char *format, ...)
+ __attribute__((format(gnu_printf, 4, 5)));
+
+const log_message *log_read_next1(int flags);
+const log_message *log_read_next2(int flags, int *index);
+inline const log_message *log_read_next(void) { return log_read_next1(BLOCK); }
+void log_free_message(const log_message *msg);
+
+// The structure that is actually in the shared memory queue.
+union log_queue_message {
+ log_message atom;
+ log_crio_message crio;
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
diff --git a/aos/atom_code/logging/atom_logging_test.cpp b/aos/atom_code/logging/atom_logging_test.cpp
new file mode 100644
index 0000000..a97d1e9
--- /dev/null
+++ b/aos/atom_code/logging/atom_logging_test.cpp
@@ -0,0 +1,146 @@
+#include <string>
+
+#include "gtest/gtest.h"
+
+#include "aos/aos_core.h"
+#include "aos/atom_code/ipc_lib/sharedmem_test_setup.h"
+#include "aos/common/control_loop/Timing.h"
+#include "aos/common/inttypes.h"
+#include "aos/common/time.h"
+
+using ::aos::time::Time;
+using ::testing::AssertionResult;
+using ::testing::AssertionSuccess;
+using ::testing::AssertionFailure;
+
+namespace aos {
+namespace testing {
+
+static const std::string kLoggingName = "LoggingTestName";
+
+class LoggingTest : public SharedMemTestSetup {
+ virtual void SetUp() {
+ SharedMemTestSetup::SetUp();
+ ASSERT_EQ(0, log_init(kLoggingName.c_str()));
+ }
+ virtual void TearDown() {
+ log_uninit();
+ SharedMemTestSetup::TearDown();
+ }
+
+ public:
+ AssertionResult WasAnythingLogged() {
+ const log_message *msg = log_read_next1(NON_BLOCK);
+ if (msg != NULL) {
+ char bad_msg[LOG_MESSAGE_LEN];
+ memcpy(bad_msg, msg->message, sizeof(bad_msg));
+ log_free_message(msg);
+ return AssertionSuccess() << "read message '" << bad_msg << "'";
+ }
+ return AssertionFailure();
+ }
+ AssertionResult WasLogged(log_level level, const std::string value) {
+ const log_message *msg = NULL;
+ char bad_msg[LOG_MESSAGE_LEN];
+ bad_msg[0] = '\0';
+ const pid_t owner = getpid();
+ while (true) {
+ if (msg != NULL) {
+ static_assert(sizeof(bad_msg) == sizeof(msg->message),
+ "something is wrong");
+ if (bad_msg[0] != '\0') {
+ printf("read bad message: %s", bad_msg);
+ }
+ memcpy(bad_msg, msg->message, sizeof(bad_msg));
+ log_free_message(msg);
+ msg = NULL;
+ }
+ msg = log_read_next1(NON_BLOCK);
+ if (msg == NULL) {
+ return AssertionFailure() << "last message read was '" << bad_msg << "'"
+ " instead of '" << value << "'";
+ }
+ if (msg->source != owner) continue;
+ if (msg->level != level) continue;
+ if (strcmp(msg->name, kLoggingName.c_str()) != 0) continue;
+ if (strcmp(msg->message + strlen(msg->message) - value.length(),
+ value.c_str()) != 0) continue;
+
+ // if it's gotten this far, then the message is correct
+ log_free_message(msg);
+ return AssertionSuccess();
+ }
+ }
+};
+typedef LoggingTest LoggingDeathTest;
+
+// Tests both basic logging functionality and that the test setup works
+// correctly.
+TEST_F(LoggingTest, Basic) {
+ EXPECT_FALSE(WasAnythingLogged());
+ LOG(INFO, "test log 1\n");
+ EXPECT_TRUE(WasLogged(INFO, "test log 1\n"));
+ LOG(INFO, "test log 1.5\n");
+ // there's a subtle typo on purpose...
+ EXPECT_FALSE(WasLogged(INFO, "test log 15\n"));
+ LOG(ERROR, "test log 2=%d\n", 55);
+ EXPECT_TRUE(WasLogged(ERROR, "test log 2=55\n"));
+ LOG(ERROR, "test log 3\n");
+ EXPECT_FALSE(WasLogged(WARNING, "test log 3\n"));
+ LOG(WARNING, "test log 4\n");
+ EXPECT_TRUE(WasAnythingLogged());
+}
+TEST_F(LoggingTest, Cork) {
+ static const int begin_line = __LINE__;
+ LOG_CORK("first part ");
+ LOG_CORK("second part (=%d) ", 19);
+ EXPECT_FALSE(WasAnythingLogged());
+ LOG_CORK("third part ");
+ static const int end_line = __LINE__;
+ LOG_UNCORK(WARNING, "last part %d\n", 5);
+ char *expected;
+ ASSERT_GT(asprintf(&expected, "atom_logging_test.cpp: %d-%d: "
+ "first part second part (=19) third part last part 5\n",
+ begin_line + 1, end_line + 1), 0);
+ EXPECT_TRUE(WasLogged(WARNING, std::string(expected)));
+}
+
+TEST_F(LoggingDeathTest, Fatal) {
+ ASSERT_EXIT(LOG(FATAL, "this should crash it\n"),
+ ::testing::KilledBySignal(SIGABRT),
+ "this should crash it");
+}
+
+TEST_F(LoggingTest, PrintfDirectives) {
+ LOG(INFO, "test log %%1 %%d\n");
+ EXPECT_TRUE(WasLogged(INFO, "test log %1 %d\n"));
+ LOG_DYNAMIC(WARNING, "test log %%2 %%f\n");
+ EXPECT_TRUE(WasLogged(WARNING, "test log %2 %f\n"));
+ LOG_CORK("log 3 part %%1 %%d ");
+ LOG_UNCORK(DEBUG, "log 3 part %%2 %%f\n");
+ EXPECT_TRUE(WasLogged(DEBUG, "log 3 part %1 %d log 3 part %2 %f\n"));
+}
+
+// For writing only.
+TEST_F(LoggingTest, Timing) {
+ static const long kTimingCycles = 5000;
+ Time start = Time::Now();
+ for (long i = 0; i < kTimingCycles; ++i) {
+ LOG(INFO, "a\n");
+ }
+ Time elapsed = Time::Now() - start;
+
+ printf("short message took %"PRId64" nsec for %ld\n", elapsed.ToNSec(),
+ kTimingCycles);
+
+ start = Time::Now();
+ for (long i = 0; i < kTimingCycles; ++i) {
+ LOG(INFO, "something longer than just \"a\" to log to test timing\n");
+ }
+ elapsed = Time::Now() - start;
+ printf("long message took %"PRId64" nsec for %ld\n", elapsed.ToNSec(),
+ kTimingCycles);
+}
+
+} // namespace testing
+} // namespace aos
diff --git a/aos/atom_code/logging/logging.gyp b/aos/atom_code/logging/logging.gyp
new file mode 100644
index 0000000..5d29da8
--- /dev/null
+++ b/aos/atom_code/logging/logging.gyp
@@ -0,0 +1,15 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'atom_logging_test',
+ 'type': 'executable',
+ 'sources': [
+ 'atom_logging_test.cpp',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ ],
+}
diff --git a/aos/atom_code/messages/DriverStationDisplay.cpp b/aos/atom_code/messages/DriverStationDisplay.cpp
new file mode 100644
index 0000000..e48a1eb
--- /dev/null
+++ b/aos/atom_code/messages/DriverStationDisplay.cpp
@@ -0,0 +1,54 @@
+#include "DriverStationDisplay.h"
+
+#include <stdarg.h>
+#include <stdio.h>
+
+using namespace aos;
+
+static const aos_type_sig signature = {sizeof(DriverStationDisplay), 1234, 10};
+aos_queue *DriverStationDisplay::queue = NULL;
+void DriverStationDisplay::GetQueue() {
+ if (queue == NULL) {
+ queue = aos_fetch_queue("DriverStationDisplay", &signature);
+ }
+}
+
+void DriverStationDisplay::Send(int line, const char *fmt, ...) {
+ GetQueue();
+ DriverStationDisplay *msg = static_cast<DriverStationDisplay *>(
+ aos_queue_get_msg(queue));
+ if (msg == NULL) {
+ LOG(WARNING, "could not get message to send '%s' to the DS queue\n", fmt);
+ return;
+ }
+ msg->line = static_cast<uint8_t>(line);
+
+ va_list ap;
+ va_start(ap, fmt);
+ int ret = vsnprintf(msg->data, sizeof(msg->data), fmt, ap);
+ va_end(ap);
+ if (ret < 0) {
+ LOG(WARNING, "could not format '%s' with arguments\n", fmt);
+ aos_queue_free_msg(queue, msg);
+ return;
+ } else if (static_cast<uintmax_t>(ret) >=
+ static_cast<uintmax_t>(sizeof(msg->data))) {
+ LOG(WARNING, "format '%s' ended up longer than the max size (%zd)\n",
+ fmt, sizeof(msg->data));
+ }
+
+ if (aos_queue_write_msg(queue, msg, NON_BLOCK) < 0) {
+ LOG(ERROR, "writing '%s' (line %hhd) failed\n", msg->data, msg->line);
+ aos_queue_free_msg(queue, msg);
+ }
+}
+
+const DriverStationDisplay *DriverStationDisplay::GetNext() {
+ GetQueue();
+ return static_cast<const DriverStationDisplay *>(aos_queue_read_msg(queue, NON_BLOCK));
+}
+void DriverStationDisplay::Free(const DriverStationDisplay *msg) {
+ GetQueue();
+ aos_queue_free_msg(queue, msg);
+}
+
diff --git a/aos/atom_code/messages/DriverStationDisplay.h b/aos/atom_code/messages/DriverStationDisplay.h
new file mode 100644
index 0000000..9ce3712
--- /dev/null
+++ b/aos/atom_code/messages/DriverStationDisplay.h
@@ -0,0 +1,31 @@
+#ifndef AOS_ATOM_CODE_MESSAGES_DRIVER_STATION_DISPLAY_H_
+#define AOS_ATOM_CODE_MESSAGES_DRIVER_STATION_DISPLAY_H_
+
+#include <stdint.h>
+#include <string.h>
+
+#include "aos/aos_core.h"
+#include "aos/common/type_traits.h"
+
+namespace aos {
+const size_t kLineLength = 21;
+
+struct DriverStationDisplay {
+ static void Send(int line, const char *fmt, ...)
+ __attribute__((format(printf, 2, 3)));
+ static const DriverStationDisplay *GetNext(); // returns NULL if there are no more
+ static void Free(const DriverStationDisplay *msg);
+
+ uint8_t line;
+ char data[kLineLength + 1];
+
+ private:
+ static void GetQueue();
+ static aos_queue *queue;
+};
+static_assert(shm_ok<DriverStationDisplay>::value,
+ "DriverStationDisplay will go through shared memory");
+} // namespace aos
+
+#endif
+
diff --git a/aos/atom_code/messages/messages.gyp b/aos/atom_code/messages/messages.gyp
new file mode 100644
index 0000000..ddbe9ec
--- /dev/null
+++ b/aos/atom_code/messages/messages.gyp
@@ -0,0 +1,38 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'messages_so',
+ 'type': 'shared_library',
+ 'variables': {'no_rsync': 1},
+ 'sources': [
+ 'DriverStationDisplay.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:aos_shared_lib',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/build/aos.gyp:aos_shared_lib',
+ ],
+ 'direct_dependent_settings': {
+ 'variables': {
+ 'jni_libs': [
+ 'messages_so',
+ ],
+ },
+ },
+ },
+ {
+ 'target_name': 'messages',
+ 'type': 'static_library',
+ 'sources': [
+ 'DriverStationDisplay.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/atom_code/ipc_lib/ipc_lib.gyp:ipc_lib'
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/atom_code/ipc_lib/ipc_lib.gyp:ipc_lib'
+ ],
+ },
+ ],
+}
diff --git a/aos/atom_code/output/HTTPServer.cpp b/aos/atom_code/output/HTTPServer.cpp
new file mode 100644
index 0000000..88e3c6f
--- /dev/null
+++ b/aos/atom_code/output/HTTPServer.cpp
@@ -0,0 +1,153 @@
+#include "aos/atom_code/output/HTTPServer.h"
+
+#include <inttypes.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <fcntl.h>
+
+#include <memory>
+
+#include "event2/event.h"
+
+#include "aos/aos_core.h"
+#include "aos/common/scoped_fd.h"
+#include "aos/common/unique_malloc_ptr.h"
+
+namespace aos {
+namespace http {
+
+HTTPServer::HTTPServer(const char *directory, uint16_t port) :
+ directory_(directory), base_(event_base_new()), http_(evhttp_new(base_)) {
+ if (base_ == NULL) {
+ LOG(FATAL, "couldn't create an event_base\n");
+ }
+ if (http_ == NULL) {
+ LOG(FATAL, "couldn't create an evhttp\n");
+ }
+ if (evhttp_bind_socket(http_, "0.0.0.0", port) != 0) {
+ LOG(FATAL, "evhttp_bind_socket(%p, \"0.0.0.0\", %"PRIu16") failed\n",
+ http_, port);
+ }
+ evhttp_set_gencb(http_, StaticServeFile, this);
+}
+
+void HTTPServer::AddPage(const std::string &path,
+ void (*handler)(evhttp_request *, void *), void *data) {
+ switch (evhttp_set_cb(http_, path.c_str(), handler, data)) {
+ case 0:
+ LOG(DEBUG, "set callback handler for '%s'\n", path.c_str());
+ break;
+ case -1:
+ LOG(INFO, "changed callback handler for '%s'\n", path.c_str());
+ break;
+ default:
+ LOG(WARNING, "evhttp_set_cb(%p, %s, %p, %p) failed\n", http_, path.c_str(),
+ handler, data);
+ break;
+ }
+}
+
+void HTTPServer::AddStandardHeaders(evhttp_request *request) {
+ if (evhttp_add_header(evhttp_request_get_output_headers(request),
+ "Server", "aos::HTTPServer/0.0") == -1) {
+ LOG(WARNING, "adding Server header failed\n");
+ }
+}
+
+namespace {
+// All of these functions return false, NULL, or -1 if they fail (and send back
+// an error).
+
+// Returns the path of the file that is being requested.
+const char *GetPath(evhttp_request *request) {
+ // Docs are unclear whether this needs freeing, but it looks like it just
+ // returns an internal field of the request.
+ // Running valgrind with no freeing of uri or path doesn't report anything
+ // related to this code.
+ const evhttp_uri *uri = evhttp_request_get_evhttp_uri(request);
+ const char *path = evhttp_uri_get_path(uri);
+ if (path == NULL) {
+ evhttp_send_error(request, HTTP_BADREQUEST, "need a path");
+ return NULL;
+ }
+ if (strstr(path, "..") != NULL) {
+ evhttp_send_error(request, HTTP_NOTFOUND, "no .. allowed!!");
+ return NULL;
+ }
+ return path;
+}
+// Returns an fd open for reading for the file at "directory/path".
+int OpenFile(evhttp_request *request, const char *path,
+ const char *directory) {
+ char *temp;
+ if (asprintf(&temp, "%s/%s", directory, path) == -1) {
+ LOG(WARNING, "asprintf(%p, \"%%s/%%s\", %p, %p) failed with %d: %s\n",
+ &temp, directory, path, errno, strerror(errno));
+ evhttp_send_error(request, HTTP_INTERNAL, NULL);
+ return -1;
+ }
+ const unique_c_ptr<char> filename(temp);
+ ScopedFD file(open(filename.get(), O_RDONLY));
+ if (!file) {
+ if (errno == ENOENT) {
+ evhttp_send_error(request, HTTP_NOTFOUND, NULL);
+ return -1;
+ }
+ LOG(ERROR, "open('%s', 0) failed with %d: %s\n", filename.get(),
+ errno, strerror(errno));
+ evhttp_send_error(request, HTTP_INTERNAL, NULL);
+ return -1;
+ }
+ return file.release();
+}
+// Returns the size of the file specified by the given fd.
+off_t GetSize(int file) {
+ struct stat info;
+ if (fstat(file, &info) == -1) {
+ LOG(ERROR, "stat(%d, %p) failed with %d: %s\n", file, &info,
+ errno, strerror(errno));
+ return -1;
+ }
+ return info.st_size;
+}
+bool SendFileResponse(evhttp_request *request, int file_num) {
+ ScopedFD file(file_num);
+ const off_t size = GetSize(file.get());
+ if (size == -1) {
+ evhttp_send_error(request, HTTP_INTERNAL, NULL);
+ return false;
+ }
+ evbuffer *const buf = evhttp_request_get_output_buffer(request);
+ if (evbuffer_add_file(buf, file.get(), 0, size) == -1) {
+ LOG(WARNING, "evbuffer_add_file(%p, %d, 0, %jd) failed\n", buf,
+ file.get(), static_cast<intmax_t>(size));
+ evhttp_send_error(request, HTTP_INTERNAL, NULL);
+ return false;
+ } else {
+ // it succeeded, so evhttp takes ownership
+ file.release();
+ }
+ evhttp_send_reply(request, HTTP_OK, NULL, NULL);
+ return true;
+}
+
+} // namespace
+void HTTPServer::ServeFile(evhttp_request *request) {
+ AddStandardHeaders(request);
+
+ const char *path = GetPath(request);
+ if (path == NULL) return;
+
+ ScopedFD file(OpenFile(request, path, directory_));
+ if (!file) return;
+
+ if (!SendFileResponse(request, file.release())) return;
+}
+
+void HTTPServer::Run() {
+ event_base_dispatch(base_);
+ LOG(FATAL, "event_base_dispatch returned\n");
+}
+
+} // namespace http
+} // namespace aos
diff --git a/aos/atom_code/output/HTTPServer.h b/aos/atom_code/output/HTTPServer.h
new file mode 100644
index 0000000..99eb295
--- /dev/null
+++ b/aos/atom_code/output/HTTPServer.h
@@ -0,0 +1,58 @@
+#include "event2/buffer.h"
+#include "event2/http.h"
+
+#include <string>
+
+namespace aos {
+namespace http {
+
+// An HTTP server that serves files from a directory using libevent.
+// Also allows configuring certain URLs to be dynamically generated.
+class HTTPServer {
+ public:
+ HTTPServer(const char *directory, uint16_t port);
+ // Starts serving pages.
+ // Might not clean up everything before returning.
+ void Run();
+ protected:
+ template<class T> class MemberHandler {
+ public:
+ typedef void (T::*Handler)(evhttp_request *);
+ struct Holder {
+ T *self;
+ Handler handler;
+ };
+ static void Call(evhttp_request *request, void *handler_in) {
+ const Holder *const holder = static_cast<Holder *>(handler_in);
+ AddStandardHeaders(request);
+ ((holder->self)->*(holder->handler))(request);
+ }
+ };
+ void AddPage(const std::string &path, void (*handler)(evhttp_request *, void *),
+ void *data);
+ template<class T> void AddPage(const std::string &path,
+ typename MemberHandler<T>::Handler handler,
+ T *self) {
+ // have to put "typename" in, so the typedef makes it clearer
+ typedef typename MemberHandler<T>::Holder HolderType;
+ AddPage(path, MemberHandler<T>::Call, new HolderType{self, handler});
+ }
+ // This gets set up as the generic handler.
+ // It can also be called separately to serve the file that the request is
+ // requesting from the filesystem.
+ void ServeFile(evhttp_request *request);
+ private:
+ // The directory where files to be served come from.
+ const char *directory_;
+ // The main libevent structure.
+ event_base *const base_;
+ // The libevent HTTP server handle.
+ evhttp *const http_;
+ static void AddStandardHeaders(evhttp_request *request);
+ static void StaticServeFile(evhttp_request *request, void *self) {
+ static_cast<HTTPServer *>(self)->ServeFile(request);
+ }
+};
+
+} // namespace http
+} // namespace aos
diff --git a/aos/atom_code/output/MotorOutput.cpp b/aos/atom_code/output/MotorOutput.cpp
new file mode 100644
index 0000000..ecbdf8b
--- /dev/null
+++ b/aos/atom_code/output/MotorOutput.cpp
@@ -0,0 +1,78 @@
+#include "aos/atom_code/output/MotorOutput.h"
+
+#include <math.h>
+
+#include "aos/common/Configuration.h"
+#include "aos/aos_core.h"
+#include "aos/common/byteorder.h"
+#include "aos/common/control_loop/Timing.h"
+#include "aos/atom_code/messages/DriverStationDisplay.h"
+
+namespace aos {
+
+MotorOutput::MotorOutput() : sock(NetworkPort::kMotors,
+ configuration::GetIPAddress(configuration::NetworkDevice::kCRIO)) {}
+
+void MotorOutput::Run() {
+ while (true) {
+ time::PhasedLoopXMS(5, 1000);
+ RunIteration();
+
+ // doesn't matter if multiple instances end up running this loop at the same
+ // time because the queue handles the race conditions
+ while (true) {
+ const aos::DriverStationDisplay *line = aos::DriverStationDisplay::GetNext();
+ if (line != NULL) {
+ AddDSLine(line->line, line->data);
+ LOG(DEBUG, "got a line %hhd that said '%s'\n", line->line, line->data);
+ aos::DriverStationDisplay::Free(line);
+ } else {
+ break;
+ }
+ }
+
+ if (sock.SendHoldMsg() == -1) {
+ LOG(WARNING, "sending outputs failed\n");
+ continue;
+ } else {
+ LOG(DEBUG, "sent outputs\n");
+ }
+ }
+}
+
+int MotorOutput::AddMotor(char type, uint8_t num, float value) {
+ if (sock.hold_msg_len_ + 4 > sock.MAX_MSG) {
+ return -1;
+ }
+ sock.hold_msg_[sock.hold_msg_len_ ++] = type;
+ sock.hold_msg_[sock.hold_msg_len_ ++] = num;
+ to_network(&value, &sock.hold_msg_[sock.hold_msg_len_]);
+ sock.hold_msg_len_ += 4;
+ return 0;
+}
+int MotorOutput::AddSolenoid(uint8_t port, bool on) {
+ if (sock.hold_msg_len_ + 3 > sock.MAX_MSG) {
+ return -1;
+ }
+ sock.hold_msg_[sock.hold_msg_len_ ++] = 's';
+ sock.hold_msg_[sock.hold_msg_len_ ++] = port;
+ sock.hold_msg_[sock.hold_msg_len_ ++] = on ? 1 : 0;
+ return 0;
+}
+
+int MotorOutput::AddDSLine(uint8_t line, const char *data) {
+ size_t data_len = strlen(data); // doesn't include terminating NULL
+ if (sock.hold_msg_len_ + 3 + data_len > sock.MAX_MSG) {
+ return -1;
+ }
+
+ sock.hold_msg_[sock.hold_msg_len_ ++] = 'd';
+ sock.hold_msg_[sock.hold_msg_len_ ++] = line;
+ sock.hold_msg_[sock.hold_msg_len_ ++] = data_len;
+ memcpy(&sock.hold_msg_[sock.hold_msg_len_], data, data_len);
+ sock.hold_msg_len_ += data_len;
+ return 0;
+}
+
+} // namespace aos
+
diff --git a/aos/atom_code/output/MotorOutput.h b/aos/atom_code/output/MotorOutput.h
new file mode 100644
index 0000000..925139a
--- /dev/null
+++ b/aos/atom_code/output/MotorOutput.h
@@ -0,0 +1,74 @@
+#ifndef AOS_ATOM_CODE_OUTPUT_MOTOR_OUTPUT_H_
+#define AOS_ATOM_CODE_OUTPUT_MOTOR_OUTPUT_H_
+
+#include <stdint.h>
+#include <string.h>
+#include <algorithm>
+#include <string>
+
+#include "aos/common/network/SendSocket.h"
+#include "aos/common/byteorder.h"
+#include "aos/common/type_traits.h"
+
+namespace aos {
+
+class MotorOutput {
+ public:
+ MotorOutput();
+ void Run();
+
+ // Constants for the first argument of AddMotor.
+ static const char VICTOR = 'v';
+ static const char TALON = 't';
+
+ protected:
+ // num is 1-indexed
+ int AddMotor(char type, uint8_t num, float value);
+ int AddSolenoid(uint8_t num, bool on);
+ int AddDSLine(uint8_t line, const char *data);
+ // loop_queuegroup is expected to be a control loop queue group.
+ // This function will fetch the latest goal and serve it.
+ template <class T>
+ int AddControlLoopGoal(T *loop_queuegroup);
+
+ virtual void RunIteration() = 0;
+
+ private:
+ SendSocket sock;
+};
+
+template <class T>
+int MotorOutput::AddControlLoopGoal(T *loop_queuegroup) {
+ typedef typename std::remove_reference<
+ decltype(*(loop_queuegroup->goal.MakeMessage().get()))>::type GoalType;
+ // TODO(aschuh): This assumes a static serialized message size.
+ const uint16_t size = GoalType::Size();
+ if (sock.hold_msg_len_ + 4 + 1 + size > sock.MAX_MSG) {
+ return -1;
+ }
+
+ const bool zero = !loop_queuegroup->goal.FetchLatest();
+
+ sock.hold_msg_[sock.hold_msg_len_ ++] = 'g';
+ const uint32_t hash = loop_queuegroup->hash();
+
+ // Place the loop hash at the front.
+ to_network(&hash, &sock.hold_msg_[sock.hold_msg_len_]);
+ sock.hold_msg_len_ += 4;
+
+ if (zero) {
+ GoalType zero_message;
+ zero_message.Zero();
+ zero_message.Serialize(&sock.hold_msg_[sock.hold_msg_len_]);
+ sock.hold_msg_len_ += size;
+ return -1;
+ } else {
+ loop_queuegroup->goal->Serialize(&sock.hold_msg_[sock.hold_msg_len_]);
+ sock.hold_msg_len_ += size;
+ return 0;
+ }
+}
+
+} // namespace aos
+
+#endif
diff --git a/aos/atom_code/output/evhttp_ctemplate_emitter.cc b/aos/atom_code/output/evhttp_ctemplate_emitter.cc
new file mode 100644
index 0000000..ed2a83f
--- /dev/null
+++ b/aos/atom_code/output/evhttp_ctemplate_emitter.cc
@@ -0,0 +1,18 @@
+#include "aos/atom_code/output/evhttp_ctemplate_emitter.h"
+
+#include "aos/aos_core.h"
+
+namespace aos {
+namespace http {
+
+void EvhttpCtemplateEmitter::Emit(const char *s, size_t slen) {
+ if (error_) return;
+ if (evbuffer_add(buf_, s, slen) != 0) {
+ LOG(ERROR, "evbuffer_add(%p, %p, %zd) failed\n",
+ buf_, s, slen);
+ error_ = true;
+ }
+}
+
+} // namespace http
+} // namespace aos
diff --git a/aos/atom_code/output/evhttp_ctemplate_emitter.h b/aos/atom_code/output/evhttp_ctemplate_emitter.h
new file mode 100644
index 0000000..d20d2cb
--- /dev/null
+++ b/aos/atom_code/output/evhttp_ctemplate_emitter.h
@@ -0,0 +1,34 @@
+#ifndef AOS_ATOM_CODE_OUTPUT_EVHTTP_CTEMPLATE_EMITTER_H_
+#define AOS_ATOM_CODE_OUTPUT_EVHTTP_CTEMPLATE_EMITTER_H_
+
+#include <string.h>
+
+#include "event2/buffer.h"
+#include "ctemplate/template_emitter.h"
+
+namespace aos {
+namespace http {
+
+// Writes everything directly into an evbuffer*.
+// Handles errors by refusing to write anything else into the buffer and storing
+// the state (which can be retrieved with error()).
+class EvhttpCtemplateEmitter : public ctemplate::ExpandEmitter {
+ public:
+ EvhttpCtemplateEmitter(evbuffer *buf) : buf_(buf), error_(false) {}
+ virtual void Emit(char c) { Emit(&c, 1); };
+ virtual void Emit(const std::string& s) { Emit(s.data(), s.size()); };
+ virtual void Emit(const char* s) { Emit(s, strlen(s)); }
+ virtual void Emit(const char* s, size_t slen);
+ // Retrieves whether or not there has been an error. If true, the error will
+ // already have been logged.
+ bool error() { return error_; }
+
+ private:
+ evbuffer *const buf_;
+ bool error_;
+};
+
+} // namespace http
+} // namespace aos
+
+#endif // AOS_ATOM_CODE_OUTPUT_EVHTTP_CTEMPLATE_EMITTER_H_
diff --git a/aos/atom_code/output/output.gyp b/aos/atom_code/output/output.gyp
new file mode 100644
index 0000000..3e4abd4
--- /dev/null
+++ b/aos/atom_code/output/output.gyp
@@ -0,0 +1,35 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'http_server',
+ 'type': 'static_library',
+ 'sources': [
+ 'HTTPServer.cpp',
+ 'evhttp_ctemplate_emitter.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(EXTERNALS):libevent',
+ '<(EXTERNALS):ctemplate',
+ ],
+ 'export_dependent_settings': [
+# Our headers #include headers from both of these.
+ '<(EXTERNALS):libevent',
+ '<(EXTERNALS):ctemplate',
+ ],
+ },
+ {
+ 'target_name': 'motor_output',
+ 'type': 'static_library',
+ 'sources': [
+ 'MotorOutput.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ ],
+}
diff --git a/aos/atom_code/queue-tmpl.h b/aos/atom_code/queue-tmpl.h
new file mode 100644
index 0000000..2c6e4e4
--- /dev/null
+++ b/aos/atom_code/queue-tmpl.h
@@ -0,0 +1,263 @@
+namespace aos {
+
+template <class T>
+bool ScopedMessagePtr<T>::Send() {
+ assert(msg_ != NULL);
+ msg_->SetTimeToNow();
+ assert(queue_ != NULL);
+ bool return_value = aos_queue_write_msg_free(queue_, msg_, OVERRIDE) == 0;
+ msg_ = NULL;
+ return return_value;
+}
+
+template <class T>
+bool ScopedMessagePtr<T>::SendBlocking() {
+ assert(msg_ != NULL);
+ msg_->SetTimeToNow();
+ assert(queue_ != NULL);
+ bool return_value = aos_queue_write_msg_free(queue_, msg_, BLOCK) == 0;
+ msg_ = NULL;
+ return return_value;
+}
+
+template <class T>
+void ScopedMessagePtr<T>::reset(T *msg) {
+ if (queue_ != NULL && msg_ != NULL) {
+ aos_queue_free_msg(queue_, msg_);
+ }
+ msg_ = msg;
+}
+
+// A SafeScopedMessagePtr<> manages a message pointer.
+// It frees it properly when the ScopedMessagePtr<> goes out of scope or gets
+// sent. By design, there is no way to get the ScopedMessagePtr to release the
+// message pointer. When the message gets sent, it allocates a queue message,
+// copies the data into it, and then sends it. Copies copy the message.
+template <class T>
+class SafeScopedMessagePtr {
+ public:
+ // Returns a pointer to the message.
+ // This stays valid until Send or the destructor have been called.
+ T *get() { return msg_; }
+
+ T &operator*() {
+ T *msg = get();
+ assert(msg != NULL);
+ return *msg;
+ }
+
+ T *operator->() {
+ T *msg = get();
+ assert(msg != NULL);
+ return msg;
+ }
+
+#ifndef SWIG
+ operator bool() {
+ return msg_ != NULL;
+ }
+
+ const T *get() const { return msg_; }
+
+ const T &operator*() const {
+ const T *msg = get();
+ assert(msg != NULL);
+ return *msg;
+ }
+
+ const T *operator->() const {
+ const T *msg = get();
+ assert(msg != NULL);
+ return msg;
+ }
+#endif // SWIG
+
+ // Sends the message and removes our reference to it.
+ // If the queue is full, over-rides the oldest message in it with our new
+ // message.
+ // Returns true on success, and false otherwise.
+ // The message will be freed.
+ bool Send() {
+ assert(msg_ != NULL);
+ assert(queue_ != NULL);
+ msg_->SetTimeToNow();
+ T *shm_msg = static_cast<T *>(aos_queue_get_msg(queue_));
+ if (shm_msg == NULL) {
+ return false;
+ }
+ *shm_msg = *msg_;
+ bool return_value =
+ aos_queue_write_msg_free(queue_, shm_msg, OVERRIDE) == 0;
+ reset();
+ return return_value;
+ }
+
+ // Sends the message and removes our reference to it.
+ // If the queue is full, blocks until it is no longer full.
+ // Returns true on success, and false otherwise.
+ // Frees the message.
+ bool SendBlocking() {
+ assert(msg_ != NULL);
+ assert(queue_ != NULL);
+ msg_->SetTimeToNow();
+ T *shm_msg = static_cast<T *>(aos_queue_get_msg(queue_));
+ if (shm_msg == NULL) {
+ return false;
+ }
+ *shm_msg = *msg_;
+ bool return_value = aos_queue_write_msg_free(queue_, shm_msg, BLOCK) == 0;
+ reset();
+ return return_value;
+ }
+
+ // Frees the contained message.
+ ~SafeScopedMessagePtr() {
+ reset();
+ }
+
+#ifndef SWIG
+ // Implements a move constructor to take the message pointer from the
+ // temporary object to save work.
+ SafeScopedMessagePtr(SafeScopedMessagePtr<T> &&ptr)
+ : queue_(ptr.queue_),
+ msg_(ptr.msg_) {
+ ptr.msg_ = NULL;
+ }
+#endif // SWIG
+
+ // Copy constructor actually copies the data.
+ SafeScopedMessagePtr(const SafeScopedMessagePtr<T> &ptr)
+ : queue_(ptr.queue_),
+ msg_(NULL) {
+ reset(new T(*ptr.get()));
+ }
+#ifndef SWIG
+ // Equal operator copies the data.
+ void operator=(const SafeScopedMessagePtr<T> &ptr) {
+ queue_ = ptr.queue_;
+ reset(new T(*ptr.get()));
+ }
+#endif // SWIG
+
+ private:
+ // Provide access to private constructor.
+ friend class aos::Queue<typename std::remove_const<T>::type>;
+ friend class aos::SafeMessageBuilder<T>;
+
+ // Only Queue should be able to build a message pointer.
+ SafeScopedMessagePtr(aos_queue *queue)
+ : queue_(queue), msg_(new T()) {}
+
+ // Sets the pointer to msg, freeing the old value if it was there.
+ // This is private because nobody should be able to get a pointer to a message
+ // that needs to be scoped without using the queue.
+ void reset(T *msg = NULL) {
+ if (msg_) {
+ delete msg_;
+ }
+ msg_ = msg;
+ }
+
+ // Sets the queue that owns this message.
+ void set_queue(aos_queue *queue) { queue_ = queue; }
+
+ // The queue that the message is a part of.
+ aos_queue *queue_;
+ // The message or NULL.
+ T *msg_;
+};
+
+template <class T>
+void Queue<T>::Init() {
+ if (queue_ == NULL) {
+ // Signature of the message.
+ aos_type_sig kQueueSignature{sizeof(T), T::kHash, T::kQueueLength};
+
+ queue_ = aos_fetch_queue(queue_name_, &kQueueSignature);
+ queue_msg_.set_queue(queue_);
+ }
+}
+
+template <class T>
+bool Queue<T>::FetchNext() {
+ Init();
+ // TODO(aschuh): Use aos_queue_read_msg_index so that multiple readers
+ // reading don't randomly get only part of the messages.
+ // Document here the tradoffs that are part of each method.
+ const T *msg = static_cast<const T *>(aos_queue_read_msg(queue_,
+ NON_BLOCK));
+ // Only update the internal pointer if we got a new message.
+ if (msg != NULL) {
+ queue_msg_.reset(msg);
+ }
+ return msg != NULL;
+}
+
+template <class T>
+bool Queue<T>::FetchNextBlocking() {
+ Init();
+ const T *msg = static_cast<const T *>(aos_queue_read_msg(queue_, BLOCK));
+ queue_msg_.reset(msg);
+ assert (msg != NULL);
+ return true;
+}
+
+template <class T>
+bool Queue<T>::FetchLatest() {
+ Init();
+ const T *msg = static_cast<const T *>(aos_queue_read_msg(queue_,
+ FROM_END | NON_BLOCK | PEEK));
+ // Only update the internal pointer if we got a new message.
+ if (msg != NULL && msg != queue_msg_.get()) {
+ queue_msg_.reset(msg);
+ return true;
+ }
+ // The message has to get freed if we didn't use it (and aos_queue_free_msg is
+ // ok to call on NULL).
+ aos_queue_free_msg(queue_, msg);
+ return false;
+}
+
+template <class T>
+SafeScopedMessagePtr<T> Queue<T>::SafeMakeMessage() {
+ Init();
+ SafeScopedMessagePtr<T> safe_msg(queue_);
+ safe_msg->Zero();
+ return safe_msg;
+}
+
+template <class T>
+ScopedMessagePtr<T> Queue<T>::MakeMessage() {
+ Init();
+ return ScopedMessagePtr<T>(queue_, MakeRawMessage());
+}
+
+template <class T>
+T *Queue<T>::MakeRawMessage() {
+ return static_cast<T *>(aos_queue_get_msg(queue_));
+}
+
+template <class T>
+aos::MessageBuilder<T> Queue<T>::MakeWithBuilder() {
+ Init();
+ return aos::MessageBuilder<T>(queue_, MakeRawMessage());
+}
+
+
+// This builder uses the safe message pointer so that it can be safely copied
+// and used by SWIG or in places where it could be leaked.
+template <class T>
+class SafeMessageBuilder {
+ public:
+ typedef T Message;
+ bool Send();
+};
+
+template <class T>
+aos::SafeMessageBuilder<T> Queue<T>::SafeMakeWithBuilder() {
+ Init();
+ return aos::SafeMessageBuilder<T>(queue_);
+}
+
+
+} // namespace aos
diff --git a/aos/atom_code/starter/starter.cpp b/aos/atom_code/starter/starter.cpp
new file mode 100644
index 0000000..0cfddd5
--- /dev/null
+++ b/aos/atom_code/starter/starter.cpp
@@ -0,0 +1,354 @@
+#include "aos/atom_code/starter/starter.h"
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <sys/signalfd.h>
+#include <sys/types.h>
+#include <fcntl.h>
+#include <sys/inotify.h>
+#include <sys/stat.h>
+
+#include "aos/aos_core.h"
+
+void niceexit(int status);
+
+pid_t start(const char *cmd, uint8_t times) {
+ char *which_cmd, *which_cmd_stm;
+ if (asprintf(&which_cmd, "which %s", cmd) == -1) {
+ LOG_IFINIT(ERROR, "creating \"which %s\" failed with %d: %s\n",
+ cmd, errno, strerror(errno));
+ niceexit(EXIT_FAILURE);
+ }
+ if (asprintf(&which_cmd_stm, "which %s.stm", cmd) == -1) {
+ LOG_IFINIT(ERROR, "creating \"which %s.stm\" failed with %d: %s\n",
+ cmd, errno, strerror(errno));
+ niceexit(EXIT_FAILURE);
+ }
+ FILE *which = popen(which_cmd, "r");
+ char exe[CMDLEN + 5], orig_exe[CMDLEN];
+ size_t ret;
+ if ((ret = fread(orig_exe, 1, sizeof(orig_exe), which)) == CMDLEN) {
+ LOG_IFINIT(ERROR, "`which %s` was too long. not starting '%s'\n", cmd, cmd);
+ return 0;
+ }
+ orig_exe[ret] = '\0';
+ if (pclose(which) == -1) {
+ LOG_IFINIT(WARNING, "pclose failed with %d: %s\n", errno, strerror(errno));
+ }
+ free(which_cmd);
+ if (strlen(orig_exe) == 0) { // which returned nothing; check if stm exists
+ LOG_IFINIT(INFO, "%s didn't exist. trying %s.stm\n", cmd, cmd);
+ FILE *which_stm = popen(which_cmd_stm, "r");
+ if ((ret = fread(orig_exe, 1, sizeof(orig_exe), which_stm)) == CMDLEN) {
+ LOG_IFINIT(ERROR, "`which %s.stm` was too long. not starting %s\n", cmd, cmd);
+ return 0;
+ }
+ orig_exe[ret] = '\0';
+ if (pclose(which) == -1) {
+ LOG_IFINIT(WARNING, "pclose failed with %d: %s\n", errno, strerror(errno));
+ }
+ }
+ if (strlen(orig_exe) == 0) {
+ LOG_IFINIT(WARNING, "couldn't find file '%s[.stm]'. not going to start it\n",
+ cmd);
+ return 0;
+ }
+ if (orig_exe[strlen(orig_exe) - 1] != '\n') {
+ LOG_IFINIT(WARNING, "no \\n on the end of `which %s[.stm]` output ('%s')\n",
+ cmd, orig_exe);
+ } else {
+ orig_exe[strlen(orig_exe) - 1] = '\0'; // get rid of the \n
+ }
+ strncpy(exe, orig_exe, CMDLEN);
+
+ strcat(exe, ".stm");
+ struct stat st;
+ errno = 0;
+ if (stat(orig_exe, &st) != 0 && errno != ENOENT) {
+ LOG_IFINIT(ERROR, "killing everything because stat('%s') failed with %d: %s\n",
+ orig_exe, errno, strerror(errno));
+ niceexit(EXIT_FAILURE);
+ } else if (errno == ENOENT) {
+ LOG_IFINIT(WARNING, "binary '%s' doesn't exist. not starting it\n", orig_exe);
+ return 0;
+ }
+ struct stat st2;
+ // if we can confirm it's already 0 size
+ bool orig_zero = stat(orig_exe, &st2) == 0 && st2.st_size == 0;
+ if (!orig_zero) {
+ // if it failed and it wasn't because it was missing
+ if (unlink(exe) != 0 && (errno != EROFS && errno != ENOENT)) {
+ LOG_IFINIT(ERROR,
+ "killing everything because unlink('%s') failed with %d: %s\n",
+ exe, errno, strerror(errno));
+ niceexit(EXIT_FAILURE);
+ }
+ if (link(orig_exe, exe) != 0) {
+ LOG_IFINIT(ERROR,
+ "killing everything because link('%s', '%s') failed with %d: %s\n",
+ orig_exe, exe, errno, strerror(errno));
+ niceexit(EXIT_FAILURE);
+ }
+ }
+ if (errno == EEXIST) {
+ LOG_IFINIT(INFO, "exe ('%s') already existed\n", exe);
+ }
+
+ pid_t child;
+ if ((child = fork()) == 0) {
+ execlp(exe, orig_exe, static_cast<char *>(NULL));
+ LOG_IFINIT(ERROR,
+ "killing everything because execlp('%s', '%s', NULL) "
+ "failed with %d: %s\n",
+ exe, cmd, errno, strerror(errno));
+ _exit(EXIT_FAILURE); // don't niceexit or anything because this is the child!!
+ }
+ if (child == -1) {
+ LOG_IFINIT(WARNING, "fork on '%s' failed with %d: %s",
+ cmd, errno, strerror(errno));
+ if (times < 100) {
+ return start(cmd, times + 1);
+ } else {
+ LOG_IFINIT(ERROR, "tried to start '%s' too many times. giving up\n", cmd);
+ return 0;
+ }
+ } else {
+ children[child] = cmd;
+ files[child] = orig_exe;
+ int ret = inotify_add_watch(notifyfd, orig_exe, IN_ATTRIB | IN_MODIFY);
+ if (ret < 0) {
+ LOG_IFINIT(WARNING, "inotify_add_watch('%s') failed: "
+ "not going to watch for changes to it because of %d: %s\n",
+ orig_exe, errno, strerror(errno));
+ } else {
+ watches[ret] = child;
+ mtimes[ret] = st2.st_mtime;
+ }
+ return child;
+ }
+}
+
+static bool exited = false;
+void exit_handler() {
+ if(exited) {
+ return;
+ } else {
+ exited = true;
+ }
+ fputs("starter: killing all children for exit\n", stdout);
+ for (auto it = children.begin(); it != children.end(); ++it) {
+ printf("starter: killing child %d ('%s') for exit\n", it->first, it->second);
+ kill(it->first, SIGKILL);
+ }
+ if (sigfd != 0) {
+ close(sigfd);
+ }
+ if (notifyfd != 0) {
+ close(notifyfd);
+ }
+}
+void niceexit(int status) {
+ printf("starter: niceexit(%d) EXIT_SUCCESS=%d EXIT_FAILURE=%d\n",
+ status, EXIT_SUCCESS, EXIT_FAILURE);
+ exit_handler();
+ exit(status);
+}
+
+int main(int argc, char *argv[]) {
+ if (argc < 2) {
+ fputs("starter: error: need an argument specifying what file to use\n", stderr);
+ niceexit(EXIT_FAILURE);
+ } else if(argc > 2) {
+ fputs("starter: warning: too many arguments\n", stderr);
+ }
+
+ atexit(exit_handler);
+
+ notifyfd = inotify_init1(IN_NONBLOCK);
+
+ pid_t core = start("core", 0);
+ if (core == 0) {
+ fputs("starter: error: core didn't exist\n", stderr);
+ niceexit(EXIT_FAILURE);
+ }
+ fprintf(stderr, "starter: info: core's pid is %jd\n", static_cast<intmax_t>(core));
+ FILE *pid_file = fopen("/tmp/starter.pid", "w");
+ if (pid_file == NULL) {
+ perror("fopen(/tmp/starter.pid)");
+ } else {
+ if (fprintf(pid_file, "%d", core) == -1) {
+ fprintf(stderr, "starter: error: fprintf(pid_file, core(=%d)) failed "
+ "with %d: %s",
+ core, errno, strerror(errno));
+ }
+ fclose(pid_file);
+ }
+ sleep(1);
+ if (kill(core, 0) != 0) {
+ fprintf(stderr, "starter: couldn't kill(%jd(=core), 0) because of %d: %s\n",
+ static_cast<intmax_t>(core), errno, strerror(errno));
+ niceexit(EXIT_FAILURE);
+ }
+ fputs("starter: before init\n", stdout);
+ aos::InitNRT();
+ fputs("starter: after init\n", stdout);
+
+ FILE *list = fopen(argv[1], "re");
+ char line[CMDLEN + 1];
+ char *line_copy;
+ uint8_t too_long = 0;
+ while (fgets(line, sizeof(line), list) != NULL) {
+ if (line[strlen(line) - 1] != '\n') {
+ LOG(WARNING, "command segment '%s' is too long. "
+ "increase the size of the line char[] above " __FILE__ ": %d\n",
+ line, __LINE__);
+ too_long = 1;
+ continue;
+ }
+ if (too_long) {
+ too_long = 0;
+ LOG(WARNING, "\tgot last chunk of too long line: '%s'\n", line);
+ continue; // don't try running the last little chunk
+ }
+ line[strlen(line) - 1] = '\0'; // get rid of the \n
+ line_copy = new char[strlen(line) + 1];
+ memcpy(line_copy, line, strlen(line) + 1);
+ fprintf(stderr, "starter: info: going to start \"%s\"\n", line_copy);
+ start(line_copy, 0);
+ }
+ fclose(list);
+ LOG(INFO, "started everything\n");
+
+ sigset_t mask;
+ sigemptyset (&mask);
+ sigaddset (&mask, SIGCHLD);
+ sigprocmask (SIG_BLOCK, &mask, NULL);
+ sigfd = signalfd (-1, &mask, O_NONBLOCK);
+
+ fd_set readfds;
+ FD_ZERO(&readfds);
+ siginfo_t infop;
+ signalfd_siginfo fdsi;
+ inotify_event notifyevt;
+ int ret;
+ while (1) {
+ FD_SET(sigfd, &readfds);
+ FD_SET(notifyfd, &readfds);
+ timeval timeout;
+ timeout.tv_sec = restarts.empty() ? 2 : 0;
+ timeout.tv_usec = 100000;
+ ret = select (FD_SETSIZE, &readfds, NULL, NULL, &timeout);
+
+ if (ret == 0) { // timeout
+ auto it = restarts.begin();
+ // WARNING because the message about it dying will be
+ for (; it != restarts.end(); it++) {
+ LOG(WARNING, "restarting process %d ('%s') by giving it a SIGKILL(%d)\n",
+ *it, children[*it], SIGKILL);
+ kill(*it, SIGKILL);
+ }
+ restarts.clear();
+ }
+
+ if (FD_ISSET(notifyfd, &readfds)) {
+ if ((ret = read(notifyfd, ¬ifyevt, sizeof(notifyevt))) ==
+ sizeof(notifyevt)) {
+ if (watches.count(notifyevt.wd)) {
+ struct stat st;
+ if (!children.count(watches[notifyevt.wd]) ||
+ stat(files[watches[notifyevt.wd]], &st) == 0) {
+ if (mtimes[notifyevt.wd] == st.st_mtime) {
+ LOG(DEBUG, "ignoring trigger of watch id %d (file '%s')"
+ " because mtime didn't change\n",
+ notifyevt.wd, files[watches[notifyevt.wd]]);
+ } else if (children.count(watches[notifyevt.wd])) {
+ LOG(DEBUG, "adding process %d to the restart list\n",
+ watches[notifyevt.wd]);
+ restarts.insert(watches[notifyevt.wd]);
+ } else {
+ LOG(DEBUG, "children doesn't have entry for PID %d\n",
+ watches[notifyevt.wd]);
+ }
+ } else {
+ LOG(ERROR, "stat('%s') failed with %d: %s\n",
+ files[watches[notifyevt.wd]], errno, strerror(errno));
+ }
+ } else {
+ LOG(WARNING, "no PID for watch id %d\n", notifyevt.wd);
+ }
+ } else {
+ if (ret == -1) {
+ LOG(WARNING, "read(notifyfd) failed with %d: %s", errno, strerror(errno));
+ } else {
+ LOG(WARNING, "couldn't get a whole inotify_event(%d) (only got %d)\n",
+ sizeof(notifyevt), ret);
+ }
+ }
+ }
+
+ if (FD_ISSET(sigfd, &readfds)) {
+ while(read (sigfd, &fdsi, sizeof fdsi) > 0);
+ }
+ while (1) {
+ infop.si_pid = 0;
+ if (waitid(P_ALL, 0, &infop, WEXITED | WSTOPPED | WNOHANG) == 0) {
+ if (infop.si_pid == 0) {
+ goto after_loop; // no more child process changes pending
+ }
+ switch (infop.si_code) {
+ case CLD_EXITED:
+ LOG(WARNING, "child %d (%s) exited with status %d\n",
+ infop.si_pid, children[infop.si_pid], infop.si_status);
+ break;
+ case CLD_DUMPED:
+ LOG(INFO, "child %d actually dumped core. "
+ "falling through to killed by signal case\n", infop.si_pid);
+ case CLD_KILLED:
+ LOG(WARNING, "child %d (%s) was killed by signal %d (%s)\n",
+ infop.si_pid, children[infop.si_pid], infop.si_status,
+ strsignal(infop.si_status));
+ break;
+ case CLD_STOPPED:
+ LOG(WARNING, "child %d (%s) was stopped by signal %d "
+ "(giving it a SIGCONT(%d))\n",
+ infop.si_pid, children[infop.si_pid], infop.si_status, SIGCONT);
+ kill(infop.si_pid, SIGCONT);
+ continue;
+ default:
+ LOG(WARNING, "something happened to child %d (%s) (killing it)\n",
+ infop.si_pid, children[infop.si_pid]);
+ kill(infop.si_pid, SIGKILL);
+ continue;
+ }
+ if (infop.si_pid == core) {
+ fprintf(stderr, "starter: si_code=%d CLD_EXITED=%d CLD_DUMPED=%d "
+ "CLD_KILLED=%d CLD_STOPPED=%d si_status=%d (sig '%s')\n",
+ infop.si_code, CLD_EXITED, CLD_DUMPED, CLD_KILLED,
+ CLD_STOPPED, infop.si_status, strsignal(infop.si_status));
+ // core has died. logging is down too
+ fputs("starter: error: core died. exiting\n", stderr);
+ niceexit(EXIT_FAILURE);
+ }
+
+ /*// remove all of the watches assigned to the pid that just died
+ for (auto it = watches.begin(); it != watches.end(); ++it) {
+ if (it->second == infop.si_pid) {
+ watches_to_ignore.insert(it->first);
+ }
+ }
+ for (auto it = watches_to_ignore.begin();
+ it != watches_to_ignore.end(); ++it) {
+ LOG(DEBUG, "watch id %d was on PID %d\n", *it, infop.si_pid);
+ watches.erase(*it);
+ }*/
+
+ start(children[infop.si_pid], 0);
+ LOG(DEBUG, "erasing %d from children\n", infop.si_pid);
+ children.erase(infop.si_pid);
+ } else {
+ LOG(WARNING, "waitid failed with %d: %s", errno, strerror(errno));
+ }
+ }
+after_loop: ;
+ }
+}
diff --git a/aos/atom_code/starter/starter.gyp b/aos/atom_code/starter/starter.gyp
new file mode 100644
index 0000000..44e4b08
--- /dev/null
+++ b/aos/atom_code/starter/starter.gyp
@@ -0,0 +1,23 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'starter_exe',
+ 'type': 'executable',
+ 'sources': [
+ 'starter.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ 'copies': [
+ {
+ 'destination': '<(rsync_dir)',
+ 'files': [
+ 'starter.sh',
+ 'starter_loop.sh',
+ ],
+ },
+ ],
+ },
+ ],
+}
diff --git a/aos/atom_code/starter/starter.h b/aos/atom_code/starter/starter.h
new file mode 100644
index 0000000..16bbe01
--- /dev/null
+++ b/aos/atom_code/starter/starter.h
@@ -0,0 +1,28 @@
+#ifndef __AOS_STARTER_H_
+#define __AOS_STARTER_H_
+
+#include <map>
+#include <sys/types.h>
+#include <signal.h>
+#include <stdint.h>
+#include <string>
+#include <errno.h>
+#include <string.h>
+#include <sys/wait.h>
+#include <set>
+
+using namespace std;
+
+map<pid_t, const char *> children;
+map<pid_t, const char *> files; // the names of the actual files
+map<int, pid_t> watches;
+set<pid_t> restarts;
+map<int, time_t> mtimes;
+
+int sigfd = 0;
+int notifyfd = 0;
+
+const size_t CMDLEN = 5000;
+
+#endif
+
diff --git a/aos/atom_code/starter/starter.sh b/aos/atom_code/starter/starter.sh
new file mode 100755
index 0000000..103180e
--- /dev/null
+++ b/aos/atom_code/starter/starter.sh
@@ -0,0 +1,17 @@
+#!/bin/bash
+
+#echo $$ > /var/run/`basename $0`.pid IT FORKS AFTER THIS!!!!
+insmod /home/driver/robot_code/bin/aos_module.ko
+#chrt -p 45 `pidof sshd`
+chrt -o 0 bash -c "export PATH=$PATH:/home/driver/robot_code/bin; starter_loop.sh $*" &
+#chrt -o 0 bash -c "while true; do cd /home/driver/mjpg-streamer2; ./server.sh; sleep 5; done" &
+
+# Log everything from the serial port...
+#SERIAL_LOG_FILE=$(date "/home/driver/tmp/robot_logs/serial_log.%F_%H-%M-%S")
+#chrt -o 0 bash -c "( stty -echo -echoe -echok 9600; cat > ${SERIAL_LOG_FILE} ) < /dev/ttyUSB0" &
+
+# Wireshark _everything_ we can see...
+#DUMPCAP_LOG_FILE=$(date "/home/driver/tmp/robot_logs/dumpcap.%F_%H-%M-%S")
+#DUMPCAP_STDOUT_FILE=$(date "/home/driver/tmp/robot_logs/stdout_dumpcap.%F_%H-%M-%S")
+#chrt -o 0 bash -c "dumpcap -i eth0 -w ${DUMPCAP_LOG_FILE} -f 'not port 8080 and not net 10.9.71.13' > ${DUMPCAP_STDOUT_FILE}" &
+
diff --git a/aos/atom_code/starter/starter_loop.sh b/aos/atom_code/starter/starter_loop.sh
new file mode 100755
index 0000000..b4e1d5c
--- /dev/null
+++ b/aos/atom_code/starter/starter_loop.sh
@@ -0,0 +1,7 @@
+#!/bin/bash
+
+for ((i=1; 1; i++)); do
+ starter_exe $* 1>/tmp/starter${i}_stdout 2>/tmp/starter${i}_stderr
+ sleep 2
+done
+
diff --git a/aos/atom_code/starter/testing_list.txt b/aos/atom_code/starter/testing_list.txt
new file mode 100644
index 0000000..96d412d
--- /dev/null
+++ b/aos/atom_code/starter/testing_list.txt
@@ -0,0 +1,3 @@
+../bin/LogReader
+../bin/JoystickCode
+../bin/AutoMode
diff --git a/aos/build/act_builder.rb b/aos/build/act_builder.rb
new file mode 100644
index 0000000..d98549c
--- /dev/null
+++ b/aos/build/act_builder.rb
@@ -0,0 +1,242 @@
+require File.dirname(__FILE__) + "/parser.rb"
+
+module Contents
+ class HasEntry < SimpleField
+ end
+ class Priority < SimpleField
+ def initialize
+ super :is_number
+ end
+ end
+
+ class OutputFile
+ def fillin_initials
+ @args_struct = nil # string
+ @status_struct = nil # string
+ @action_name = nil # string
+ @actions = []
+ @has = []
+ end
+ def fillin_defaults
+ @action_name = @base unless @action_name
+ @actions.push @action_name if @actions.empty?
+ @args_struct.add_hidden_field 'timespec', 'set_time'
+ @status_struct.add_hidden_field 'timespec', 'set_time'
+ end
+ def parse_token token, tokenizer
+ case token
+ when 'args'
+ throw :syntax_error, '"args" redefined' if @args_struct
+ @args_struct = Struct.parse tokenizer
+ when 'status'
+ throw :syntax_error, '"status" redefined' if @status_struct
+ @status_struct = Struct.parse tokenizer
+ when 'action_name'
+ throw :syntax_error, '"action_name" redefined' if @action_name
+ @action_name = NameField.parse tokenizer
+ when 'async_queue'
+ @actions.push(NameField.parse tokenizer)
+ when 'has'
+ @has.push(HasEntry.parse tokenizer)
+ when 'priority'
+ throw :syntax_error, '"priority" redefined' if @priority
+ @priority = Priority.parse tokenizer
+ else
+ throw :syntax_error, "unsupported field \"#{token}\""
+ end
+ end
+ def check_format tokenizer
+ tokenizer.item_missing("args") unless @args_struct
+ tokenizer.item_missing("status") unless @status_struct
+ tokenizer.item_missing("priority") unless @priority
+ end
+
+ def superclass
+ "aos::AsyncAction<#{@args_struct.name}, #{@status_struct.name}>"
+ end
+ def impl_class
+ @action_name + '_t'
+ end
+ def handle_class
+ @action_name + 'Handle'
+ end
+ def write_header
+ f = File.open(filename('h'), "w+")
+ f.puts <<END
+#ifndef AOS_GENERATED_ASYNC_ACTION_#{impl_class}_H_
+#define AOS_GENERATED_ASYNC_ACTION_#{impl_class}_H_
+// This file is autogenerated.
+// Edit #{@filename} to change its contents.
+
+#include "aos/common/messages/QueueHolder.h"
+#include "aos/atom_code/async_action/AsyncAction.h"
+#include "aos/atom_code/async_action/AsyncActionHandle.h"
+
+namespace #{$namespace} {
+#{@args_struct.writer}
+#{@status_struct.writer}
+ class #{impl_class} : public #{superclass} {
+ virtual void DoAction(#{@args_struct.name} &args __attribute__((unused))){
+ DoAction(#{@args_struct.params_from 'args'});
+ }
+ void DoAction(#{@args_struct.params});
+#{@has.grep('OnStart').empty? ? '' : "virtual void OnStart();"}
+#{@has.grep('OnEnd').empty? ? '' : "virtual void OnEnd();"}
+ using #{superclass}::PostStatus;
+ inline void PostStatus(#{@status_struct.params}){
+ #{@status_struct.copy_params_into 'new_stat'}
+ PostStatus(new_stat);
+ }
+ public:
+ #{impl_class}(const std::string name) : #{superclass}(name) {}
+#ifdef AOS_#{impl_class}_HEADER_FRAG
+ AOS_#{impl_class}_HEADER_FRAG
+#endif
+ };
+
+ class #{handle_class} : public aos::AsyncActionHandle {
+ friend class ::AsyncActionTest;
+ private:
+ const std::string name;
+ #{superclass} *instance;
+ #{superclass} &GetInstance(){
+ if(instance == NULL){
+ instance = new #{superclass}(name);
+ }
+ return *instance;
+ }
+ #{@status_struct.name} temp_status;
+ void Free(){
+ if(instance != NULL){
+ delete instance;
+ instance = NULL;
+ }
+ }
+ public:
+ inline uint16_t Start(#{@args_struct.name} &args){
+ return GetInstance().Start(args);
+ }
+ inline uint16_t Start(#{@args_struct.params}){
+ #{@args_struct.copy_params_into 'args_struct'}
+ return Start(args_struct);
+ }
+ inline void Execute(#{@args_struct.name} &args){
+ GetInstance().Join(GetInstance().Start(args));
+ }
+ inline bool Execute(#{@args_struct.params}){
+ #{@args_struct.copy_params_into 'args_struct'}
+ Execute(args_struct);
+ return GetStatus();
+ }
+ inline bool IsDone(){
+ return GetInstance().IsDone();
+ }
+ inline bool IsDone(int32_t count){
+ return GetInstance().IsDone(count);
+ }
+ inline uint16_t Join(){
+ return GetInstance().Join();
+ }
+ inline uint16_t Join(int32_t count){
+ return GetInstance().Join(count);
+ }
+ inline bool GetStatus(#{@status_struct.name} &status_out) __attribute__ ((warn_unused_result)){
+ return GetInstance().GetStatus(status_out);
+ }
+ inline bool GetStatus(#{@status_struct.name} &status_out, int32_t count) __attribute__ ((warn_unused_result)){
+ return GetInstance().GetStatus(status_out, count);
+ }
+ inline bool GetStatus() __attribute__ ((warn_unused_result)){
+ return GetInstance().GetStatus(temp_status);
+ }
+ inline bool GetStatus(int32_t count) __attribute__ ((warn_unused_result)){
+ return GetInstance().GetStatus(temp_status, count);
+ }
+ inline bool GetNextStatus(#{@status_struct.name} &status_out) __attribute__ ((warn_unused_result)){
+ return GetInstance().GetNextStatus(status_out);
+ }
+ inline bool GetNextStatus(#{@status_struct.name} &status_out, int32_t count) __attribute__ ((warn_unused_result)){
+ return GetInstance().GetNextStatus(status_out, count);
+ }
+ inline bool GetNextStatus() __attribute__ ((warn_unused_result)){
+ return GetInstance().GetNextStatus(temp_status);
+ }
+ inline bool GetNextStatus(int32_t count) __attribute__ ((warn_unused_result)){
+ return GetInstance().GetNextStatus(temp_status, count);
+ }
+ inline const #{@status_struct.name} &GetLastStatus(){
+ return temp_status;
+ }
+ inline void Stop(){
+ GetInstance().Stop();
+ }
+ inline void Stop(int32_t count){
+ GetInstance().Stop(count);
+ }
+
+ #{handle_class}(const std::string name) : name(name), instance(NULL) {}
+ };
+#{(@actions.collect do |a|
+<<END2
+ extern #{handle_class} #{a};
+END2
+end).join('')}
+
+} // namespace #{$namespace}
+
+#endif
+END
+ f.close
+ end
+ def write_cpp
+ f = File.open(filename('cc'), "w+")
+f.puts <<END
+// This file is autogenerated.
+// Edit #{@filename} to change its contents.
+
+#include "#{filename 'h'}"
+
+namespace #{$namespace} {
+
+#{(@actions.collect do |a|
+<<END2
+#{handle_class} #{a}("#{a}");
+END2
+end).join("\n")}
+
+} // namespace #{$namespace}
+END
+ f.close
+ end
+ def write_main
+ f = File.open(filename('main'), "w+")
+f.puts <<END
+// This file is autogenerated.
+// Edit #{@filename} to change its contents.
+
+#include "#{filename 'h'}"
+#include "aos/atom_code/async_action/AsyncActionRunner.h"
+#include <string>
+#include <cstring>
+#include <iostream>
+
+int main(int argc, char **argv) {
+ aos::Init();
+
+ std::string name = "#{@action_name}";
+ if(argc > 1)
+ name = std::string(argv[1]);
+ #{$namespace}::#{impl_class} action(name);
+ int rv = aos::AsyncActionRunner::Run(action, #{@priority});
+
+ aos::Cleanup();
+ return rv;
+}
+END
+ f.close
+ end
+ end
+end
+
+write_file_out
+
diff --git a/aos/build/aos.gyp b/aos/build/aos.gyp
new file mode 100644
index 0000000..b6bd3ee
--- /dev/null
+++ b/aos/build/aos.gyp
@@ -0,0 +1,156 @@
+# This file has all of the aos targets.
+# For the cRIO, shared_library means to build a .out file, NOT a shared library.
+# This means that depending on shared libraries doesn't work very well.
+# Shared libraries don't seem to be supported by the powerpc-wrs-vxworks
+# tools and gyp doesn't like a static_library that depends on static_librarys.
+{
+ 'variables': {
+ 'conditions': [
+ ['OS=="crio"', {
+ 'libaos_source_files': [
+ '<!@(find <(AOS)/crio/controls <(AOS)/crio/messages <(AOS)/crio/motor_server <(AOS)/crio/shared_libs -name *.c -or -name *.cpp -or -name *.cc)',
+ '<(AOS)/crio/Talon.cpp',
+ '<(AOS)/common/die.cc',
+ ],
+ }, {
+ 'libaos_source_files': [
+ '<(AOS)/atom_code/camera/Buffers.cpp',
+ '<(AOS)/atom_code/async_action/AsyncAction_real.cpp',
+ '<(AOS)/atom_code/init.cc',
+ '<(AOS)/atom_code/ipc_lib/mutex.cpp',
+ '<(AOS)/common/die.cc',
+ ],
+ }
+ ],
+ ],
+ },
+ 'targets': [
+ {
+ 'target_name': 'logging',
+ 'type': 'static_library',
+ 'conditions': [
+ ['OS=="crio"', {
+ 'sources': [
+ '<(AOS)/crio/logging/crio_logging.cpp',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):WPILib',
+ ]
+ }, {
+ 'sources': [
+ '<(AOS)/atom_code/logging/atom_logging.cpp'
+ ],
+ 'dependencies': [
+ '<(AOS)/atom_code/ipc_lib/ipc_lib.gyp:ipc_lib',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/atom_code/ipc_lib/ipc_lib.gyp:ipc_lib',
+ ]
+ }],
+ ],
+ 'dependencies': [
+ '<(AOS)/common/common.gyp:time',
+ ],
+ },
+ {
+# Private to make Brian happy. Don't use elsewhere in so targets or risk things
+# breaking.
+ 'target_name': 'aos_swig',
+ 'type': 'static_library',
+ 'sources': [
+ '<(AOS)/aos.swig',
+ ],
+ 'variables': {
+ 'package': 'aos',
+ },
+ 'dependencies': [
+ '<(AOS)/common/common.gyp:queues',
+ ],
+ 'includes': ['../build/swig.gypi'],
+ },
+ {
+ 'target_name': 'libaos',
+ 'type': 'static_library',
+ 'sources': ['<@(libaos_source_files)'],
+ 'sources/': [['exclude', '_test\.c[cp]*$']],
+ 'dependencies': [
+ '<(AOS)/common/messages/messages.gyp:aos_queues',
+ 'logging',
+ '<(EXTERNALS):WPILib',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/common/messages/messages.gyp:aos_queues',
+ '<(EXTERNALS):WPILib',
+ ],
+ 'conditions': [
+ ['OS=="atom"', {
+ 'dependencies': [
+ '<(AOS)/atom_code/ipc_lib/ipc_lib.gyp:ipc_lib',
+ ],
+ }]
+ ],
+ },
+ {
+ 'target_name': 'aos_shared_lib',
+ 'type': 'shared_library',
+ 'sources': ['<@(libaos_source_files)'],
+ 'sources/': [['exclude', '_test\.c[cp]*$']],
+ 'variables': {'no_rsync': 1},
+ 'dependencies': [
+ '<(AOS)/common/messages/messages.gyp:queues_so',
+ '<(AOS)/common/common.gyp:queues',
+ 'aos_swig',
+ '<(EXTERNALS):WPILib',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/common/messages/messages.gyp:queues_so',
+ '<(EXTERNALS):WPILib',
+ 'aos_swig',
+ ],
+ 'direct_dependent_settings': {
+ 'variables': {
+ 'jni_libs': [
+ 'aos_shared_lib',
+ ],
+ },
+ },
+ },
+ {
+# A target that has all the same dependencies as libaos and aos_shared_lib
+# without any queues so that the queues can get the necessary headers without
+# creating circular dependencies.
+ 'target_name': 'aos_internal_nolib',
+ 'type': 'none',
+ 'dependencies': [
+ 'aos/ResourceList.h',
+ '<(EXTERNALS):WPILib',
+ ],
+ 'export_dependent_settings': [
+ 'aos/ResourceList.h',
+ '<(EXTERNALS):WPILib',
+ ],
+ },
+ {
+ 'target_name': 'aos/ResourceList.h',
+ 'type': 'static_library',
+ 'direct_dependent_settings': {
+ 'include_dirs': [
+ '<(SHARED_INTERMEDIATE_DIR)/ResourceList',
+ ],
+ },
+ 'hard_dependency': 1,
+ 'actions': [
+ {
+ 'variables': {
+ 'script': '<(AOS)/build/gen_resource_list.rb'
+ },
+ 'action_name': 'gen_aos_ResourceList_h',
+ 'inputs': ['<(script)'],
+ 'outputs': ['<(SHARED_INTERMEDIATE_DIR)/ResourceList/aos/ResourceList.h'],
+ 'message': 'Generating',
+ 'action': ['ruby', '<(script)', '<(SHARED_INTERMEDIATE_DIR)/ResourceList/aos',],
+ },
+ ],
+ },
+ ],
+}
diff --git a/aos/build/aos.gypi b/aos/build/aos.gypi
new file mode 100644
index 0000000..08bf975
--- /dev/null
+++ b/aos/build/aos.gypi
@@ -0,0 +1,194 @@
+# This file gets passed to gyp with -I so that it gets included everywhere.
+{
+ 'variables': {
+ 'AOS': '<(DEPTH)/aos',
+# A directory with everything in it ignored from source control.
+ 'TMPDIR': '<(DEPTH)/aos/build/temp',
+ 'aos_abs': '<!(readlink -f <(DEPTH)/aos)', # for use in non-path contexts
+# the .gyp file that has targets for the various external libraries
+ 'EXTERNALS': '<(AOS)/build/externals.gyp',
+# the directory that gets rsynced to the atom
+ 'rsync_dir': '<(PRODUCT_DIR)/outputs',
+# The directory that loadable_module and shared_library targets get put into
+# There's a target_conditions that puts loadable_modules here and
+# shared_librarys automatically get put here.
+ 'so_dir': '<(PRODUCT_DIR)/lib',
+# the directory that executables that depend on <(EXTERNALS):gtest get put into
+ 'test_dir': '<(PRODUCT_DIR)/tests',
+# 'executable' for the atom and 'static_library' for the cRIO
+# Useful for targets that should either be an executable or get compiled into
+# a .out file depending on the current platform.
+# 'aos_target': platform-dependent,
+ },
+ 'conditions': [
+ ['OS=="crio"', {
+ 'make_global_settings': [
+ ['CC', '<!(which powerpc-wrs-vxworks-gcc)'],
+ ['CXX', '<!(which powerpc-wrs-vxworks-g++)'],
+ ['LD', '<!(readlink -f <(AOS)/build/crio_link_out)'],
+ #['LD', 'powerpc-wrs-vxworks-ld'],
+ #['AR', '<!(which powerpc-wrs-vxworks-ar)'],
+ #['NM', '<!(which powerpc-wrs-vxworks-nm)'],
+ ],
+ 'variables': {
+ 'aos_target': 'static_library',
+ },
+ }, {
+ 'variables': {
+ 'aos_target': 'executable',
+ },
+ }
+ ],
+ ],
+ 'target_defaults': {
+ 'defines': [
+ '__STDC_FORMAT_MACROS',
+ '_FORTIFY_SOURCE=2',
+ ],
+ 'ldflags': [
+ '-pipe',
+ ],
+ 'cflags': [
+ '-pipe',
+
+ '-Wall',
+ '-Wextra',
+ '-Wswitch-enum',
+ '-Wpointer-arith',
+ '-Wstrict-aliasing=2',
+ '-Wcast-qual',
+ '-Wcast-align',
+ '-Wwrite-strings',
+ '-Wtype-limits',
+ '-Wsign-compare',
+ '-Wformat=2',
+ '-Werror',
+ ],
+ 'cflags_c': [
+ '-std=gnu99',
+ ],
+ 'cflags_cc': [
+ '-std=gnu++0x',
+ ],
+ 'include_dirs': [
+ '<(DEPTH)',
+ ],
+ 'conditions': [
+ ['DEBUG=="yes"', {
+ 'cflags': [
+ '-ggdb3',
+ '-O0',
+ ],
+ 'ldflags': [
+ '-O3',
+ ],
+ }, {
+ 'cflags': [
+ '-O3',
+ ],
+ 'conditions': [['OS=="crio"', {
+ 'cflags': [
+ '-fstrength-reduce',
+ '-fno-builtin',
+ '-fno-strict-aliasing',
+ ],
+ }, {
+ 'cflags': [
+ # core2 says the same stuff as atom in the gcc docs but is supported by 4.4.5
+ '-march=core2',
+ '-mtune=generic',
+ '-msse3',
+ '-mfpmath=sse',
+
+ '-fstack-protector',
+ ],
+ }
+ ]],
+ }
+ ],
+ ['OS=="crio"', {
+ 'target_conditions': [
+ ['_type=="shared_library"', {
+ 'ldflags': [
+ '-r',
+ '-nostdlib',
+ '-Wl,-X',
+ ],
+ }
+ ],
+ ],
+ 'ldflags': [
+ '-mcpu=603',
+ '-mstrict-align',
+ '-mlongcall',
+ ],
+ 'cflags': [
+ '-mcpu=603',
+ '-mstrict-align',
+ '-mlongcall',
+ '-isystem', '<(aos_abs)/externals/gccdist/WindRiver/gnu/3.4.4-vxworks-6.3/x86-win32/lib/gcc/powerpc-wrs-vxworks/3.4.4/include/',
+ '-isystem', '<(aos_abs)/externals/gccdist/WindRiver/vxworks-6.3/target/h/',
+ '-isystem', '<(aos_abs)/externals/gccdist/WindRiver/gnu/3.4.4-vxworks-6.3/x86-win32/include/c++/3.4.4/',
+ '-isystem', '<(aos_abs)/externals/gccdist/WindRiver/gnu/3.4.4-vxworks-6.3/x86-win32/include/c++/3.4.4/powerpc-wrs-vxworks/',
+ '-isystem', '<(WIND_BASE)/target/h',
+ '-isystem', '<(WIND_BASE)/target/h/wrn/coreip',
+ ],
+ 'defines': [
+ 'CPU=PPC603',
+ 'TOOL_FAMILY=gnu',
+ 'TOOL=gnu',
+ '_WRS_KERNEL',
+ '__PPC__',
+# This tells eigen to not do anything with alignment at all. See
+# <http://eigen.tuxfamily.org/dox/TopicPreprocessorDirectives.html> for
+# details. It really doesn't like to work without this.
+ 'EIGEN_DONT_ALIGN',
+# prevent the vxworks system headers from being dumb and #defining min and max
+ 'NOMINMAX',
+ ],
+ }, {
+ 'variables': {
+ 'no_rsync%': 0,
+ },
+ 'target_conditions': [
+# default to putting outputs into rsync_dir
+ ['no_rsync==0 and _type!="static_library"', {
+ 'product_dir': '<(rsync_dir)',
+ },
+ ],
+ ['_type=="loadable_module"', {
+ 'product_dir': '<(so_dir)',
+ }
+ ],
+ ['_type=="loadable_module" or _type=="shared_library"', {
+ 'ldflags': [
+# Support loading other shared objects that are in the same directory but not
+# the shared object load path. Required for using the swig-generated libs.
+ '-Wl,-rpath=\\$$ORIGIN',
+ ],
+ }
+ ],
+ ],
+ 'ldflags': [
+ '-pthread',
+ '-m32',
+ ],
+ 'library_dirs': [
+ '/usr/lib32',
+ ],
+ 'cflags': [
+ '-pthread',
+ '-m32',
+ ],
+ 'defines': [
+ '_LARGEFILE64_SOURCE',
+ ],
+ 'libraries': [
+ '-lm',
+ '-lrt',
+ ],
+ }
+ ]
+ ],
+ },
+}
diff --git a/aos/build/aos_all.gyp b/aos/build/aos_all.gyp
new file mode 100644
index 0000000..a65909d
--- /dev/null
+++ b/aos/build/aos_all.gyp
@@ -0,0 +1,48 @@
+# This file has the executables etc that AOS builds.
+# User .gyp files for the atom should depend on :Atom.
+# User .gyp files for the crio should depend on :Crio.
+{
+ 'targets': [
+ {
+ 'target_name': 'Atom',
+ 'type': 'none',
+ 'variables': {
+ 'no_rsync': 1,
+ },
+ 'dependencies': [
+ '../atom_code/camera/camera.gyp:CameraHTTPStreamer',
+ '../atom_code/camera/camera.gyp:CameraReader',
+ '../atom_code/core/core.gyp:*',
+ #'../atom_code/async_action:*', # TODO(brians) fix this broken test
+ '../atom_code/ipc_lib/ipc_lib.gyp:*',
+ '../atom_code/starter/starter.gyp:*',
+ '../crio/crio.gyp:unsafe_queue_test',
+ '../common/common.gyp:queue_test',
+ #'../common/messages/messages.gyp:*', # TODO(brians) did this test ever exist?
+ '../atom_code/logging/logging.gyp:*',
+ '../common/common.gyp:die_test',
+ ':Common',
+ ],
+ },
+ {
+ 'target_name': 'Crio',
+ 'type': 'none',
+ 'dependencies': [
+ '../crio/googletest/googletest.gyp:*',
+ ':Common',
+ ],
+ },
+ {
+ 'target_name': 'Common',
+ 'type': 'none',
+ 'variables': {
+ 'no_rsync': 1,
+ },
+ 'dependencies': [
+ '<(AOS)/common/common.gyp:type_traits_test',
+ '<(AOS)/common/common.gyp:time_test',
+ '<(AOS)/common/common.gyp:mutex_test',
+ ],
+ },
+ ],
+}
diff --git a/aos/build/build.sh b/aos/build/build.sh
new file mode 100755
index 0000000..7c0362b
--- /dev/null
+++ b/aos/build/build.sh
@@ -0,0 +1,81 @@
+#!/bin/bash -e
+#set -x
+
+# This file should be called to build the code.
+# Usage: build.sh platform main_file.gyp debug [action]
+
+PLATFORM=$1
+GYP_MAIN=$2
+DEBUG=$3
+ACTION=$4
+
+export WIND_BASE=${WIND_BASE:-"/usr/local/powerpc-wrs-vxworks/wind_base"}
+
+[ ${PLATFORM} == "crio" -o ${PLATFORM} == "atom" ] || ( echo Platform "(${PLATFORM})" must be '"crio" or "atom"'. ; exit 1 )
+[ ${DEBUG} == "yes" -o ${DEBUG} == "no" ] || ( echo Debug "(${DEBUG})" must be '"yes" or "no"'. ; exit 1 )
+
+AOS=`dirname $0`/..
+NINJA_DIR=${AOS}/externals/ninja
+NINJA=${NINJA_DIR}/ninja
+# From chromium@154360:trunk/src/DEPS.
+GYP_REVISION=1488
+GYP_DIR=${AOS}/externals/gyp-${GYP_REVISION}
+GYP=${GYP_DIR}/gyp
+
+OUTDIR=${AOS}/../out_${PLATFORM}
+BUILD_NINJA=${OUTDIR}/Default/build.ninja
+
+[ -d ${NINJA_DIR} ] || git clone --branch release https://github.com/martine/ninja.git ${NINJA_DIR}
+[ -x ${NINJA} ] || ${NINJA_DIR}/bootstrap.py
+[ -d ${GYP_DIR} ] || ( svn co http://gyp.googlecode.com/svn/trunk -r ${GYP_REVISION} ${GYP_DIR} && patch -p1 -d ${GYP_DIR} < ${AOS}/externals/gyp.patch )
+${AOS}/build/download_externals.sh
+
+# The exciting quoting is so that it ends up with -DWHATEVER='"'`a command`'"'.
+# The '"' at either end is so that it creates a string constant when expanded
+# in the C/C++ code.
+COMMONFLAGS='-DLOG_SOURCENAME='"'\"'"'`basename $in`'"'\"' "
+if [ ${PLATFORM} == crio ]; then
+ COMMONFLAGS+='-DAOS_INITNAME=aos_init_function_`readlink -f $out | sed \"s/[\/.]/_/g\"` '
+fi
+
+if [[ "${ACTION}" != "clean" && ( ! -d ${OUTDIR} || -n \
+ "`find ${AOS}/.. -newer ${BUILD_NINJA} \( -name '*.gyp' -or -name '*.gypi' \)`" ) ]]; then
+ ${GYP} \
+ --check --depth=${AOS}/.. --no-circular-check -f ninja \
+ -I${AOS}/build/aos.gypi -Goutput_dir=out_${PLATFORM} \
+ -DOS=${PLATFORM} -DWIND_BASE=${WIND_BASE} -DDEBUG=${DEBUG} \
+ ${GYP_MAIN}
+ # Have to substitute "command = $compiler" so that it doesn't try to
+ # substitute them in the linker commands, where it doesn't work.
+ sed -i "s:command = \$cc:\\0 ${COMMONFLAGS}:g ; \
+ s:command = \$cxx:\\0 ${COMMONFLAGS}:g" \
+ ${BUILD_NINJA}
+ if [ ${PLATFORM} == crio ]; then
+ sed -i 's/nm -gD/nm/g' ${BUILD_NINJA}
+ fi
+fi
+
+if [ "${ACTION}" == "clean" ]; then
+ rm -r ${OUTDIR}
+else
+ if [ "${ACTION}" != "deploy" -a "${ACTION}" != "tests" ]; then
+ GYP_ACTION=${ACTION}
+ else
+ GYP_ACTION=
+ fi
+ ${NINJA} -C ${OUTDIR}/Default ${GYP_ACTION}
+ case ${ACTION} in
+ deploy)
+ [ ${PLATFORM} == atom ] && \
+ rsync --progress -t -r --rsync-path=/home/driver/bin/rsync \
+ ${OUTDIR}/Default/outputs/* \
+ driver@fitpc:/home/driver/robot_code/bin
+ [ ${PLATFORM} == crio ] && \
+ ncftpput robot / \
+ ${OUTDIR}/Default/lib/FRC_UserProgram.out
+ ;;
+ tests)
+ find ${OUTDIR}/Default/tests -executable -exec {} \;
+ ;;
+ esac
+fi
diff --git a/aos/build/create_aos_ctdt.sh b/aos/build/create_aos_ctdt.sh
new file mode 100755
index 0000000..63c927c
--- /dev/null
+++ b/aos/build/create_aos_ctdt.sh
@@ -0,0 +1,12 @@
+#!/bin/bash
+
+echo '#include "aos/crio/aos_ctdt.h"'
+calls=''
+for symbol in `cat - | awk '{ print $NF }' | grep '^aos_init_function_'`; do
+ echo "void $symbol();"
+ calls="$calls$symbol();\n"
+done
+echo 'void aos_call_init_functions() {'
+echo -e $calls
+echo '}'
+
diff --git a/aos/build/create_jar b/aos/build/create_jar
new file mode 100755
index 0000000..2ef496e
--- /dev/null
+++ b/aos/build/create_jar
@@ -0,0 +1,29 @@
+#!/bin/bash
+source `dirname $0`/jdk_tools_common
+
+# This is a helper script that compiles java files into a jar.
+
+SOURCEFILEPARENTDIRS=`echo $4 | tr -d '"'`
+SOURCEFILEDIRS=`echo $1 | tr -d '"'`
+[ -n "${SOURCEFILEPARENTDIRS}" ] && SOURCEFILEDIRS+=" `find ${SOURCEFILEPARENTDIRS} -type d -maxdepth 1`"
+SOURCEFILES=`find ${SOURCEFILEDIRS} -name *.java`
+MANIFEST_FILE=$5
+OUTPUT_JAR=$6
+HEADER_DIR=$7
+GEN_HEADERS=$8
+
+CLASSFILES_DIR=${TMPDIR}/classfiles
+
+[ -a ${CLASSFILES_DIR} ] && rm -r ${CLASSFILES_DIR}
+mkdir ${CLASSFILES_DIR}
+[ -a ${HEADER_DIR} ] && rm -r ${HEADER_DIR}
+mkdir -p ${HEADER_DIR}
+
+javac -d ${CLASSFILES_DIR} -classpath "${EXTRA_CLASSPATH}" ${SOURCEFILES}
+
+jar cfm ${OUTPUT_JAR} ${MANIFEST_FILE} \
+ `find ${CLASSFILES_DIR} -name *.class | \
+ sed "s:${CLASSFILES_DIR}/\(.*\):-C ${CLASSFILES_DIR} \1:g"`
+
+[ -z ${GEN_HEADERS} ] || javah -d ${HEADER_DIR} \
+ -classpath "${EXTRA_CLASSPATH}:${OUTPUT_JAR}" ${GEN_HEADERS}
diff --git a/aos/build/create_onejar b/aos/build/create_onejar
new file mode 100755
index 0000000..aa7ecd5
--- /dev/null
+++ b/aos/build/create_onejar
@@ -0,0 +1,26 @@
+#!/bin/bash
+source `dirname $0`/jdk_tools_common
+
+# This is a helper script that puts jars into a OneJAR package.
+
+MAIN_JAR=$1
+OUTPUT_ONEJAR=$4
+ONEJAR_JAR=$5
+SHARED_OBJECTS=$6
+
+JAR_DIR=${TMPDIR}/jardir
+
+# the dir name in the jar under which shared objects get put
+BINLIB_DIR=so_libs
+
+[ -a ${JAR_DIR} ] && rm -r ${JAR_DIR}
+mkdir ${JAR_DIR} ${JAR_DIR}/main ${JAR_DIR}/lib ${JAR_DIR}/${BINLIB_DIR}
+
+cp ${EXTRA_JARS} ${JAR_DIR}/lib
+cp ${SHARED_OBJECTS} ${JAR_DIR}/${BINLIB_DIR}
+cp ${MAIN_JAR} ${JAR_DIR}/main/main.jar
+
+unzip -q -d ${JAR_DIR} ${ONEJAR_JAR}
+cp ${JAR_DIR}/boot-manifest.mf ${TMPDIR}/manifest.mf
+echo "One-Jar-Expand: ${BINLIB_DIR}" >> ${TMPDIR}/manifest.mf
+jar cfm ${OUTPUT_ONEJAR} ${TMPDIR}/manifest.mf -C ${JAR_DIR} .
diff --git a/aos/build/crio_link_out b/aos/build/crio_link_out
new file mode 100755
index 0000000..eef549b
--- /dev/null
+++ b/aos/build/crio_link_out
@@ -0,0 +1,26 @@
+#!/bin/bash -e
+
+# This is a helper script that compiles .out files for the cRIO. It is designed
+# to be called as a replacement for g++ being used as a linker.
+
+# All the flags except -shared.
+INPUTS_FLAGS=`echo "$@" | sed 's/-shared//g'`
+# The arguments after any -o flags.
+OUTPUT=`echo ${INPUTS_FLAGS} | awk \
+ 'BEGIN { RS=" " }; output { print ; output = 0 }; /-o/ { output = 1 }'`
+# All arguments that don't start with a - and aren't ${OUTPUT}.
+#INPUTS=`echo ${INPUTS_FLAGS} | sed "s:-[^ ]*::g; s:${OUTPUT}::g;"`
+INPUTS=`echo ${INPUTS_FLAGS} | awk \
+ 'BEGIN { RS=" " }; /-Wl,--no-whole-archive/ { output = 0 }; \
+ output { print }; \
+ /-Wl,--whole-archive/ { output = 1 }'`
+TEMPDIR=`dirname ${OUTPUT}`
+AOS=`dirname $0`/..
+powerpc-wrs-vxworks-nm ${INPUTS} | \
+ tclsh ${WIND_BASE}/host/resource/hutils/tcl/munch.tcl -c ppc > ${TEMPDIR}/ctdt.c
+powerpc-wrs-vxworks-gcc -I${AOS}/.. -c ${TEMPDIR}/ctdt.c -o ${TEMPDIR}/ctdt.o
+powerpc-wrs-vxworks-nm ${INPUTS} | \
+ ${AOS}/build/create_aos_ctdt.sh > ${TEMPDIR}/aos_ctdt.c
+powerpc-wrs-vxworks-gcc -I${AOS}/.. -c ${TEMPDIR}/aos_ctdt.c -o ${TEMPDIR}/aos_ctdt.o
+powerpc-wrs-vxworks-g++ ${INPUTS_FLAGS} ${TEMPDIR}/ctdt.o ${TEMPDIR}/aos_ctdt.o
+ln -f ${OUTPUT} `echo ${OUTPUT} | sed 's/lib\([A-Za-z0-9_]*\)\.so$/\1.out/'`
diff --git a/aos/build/download_externals.sh b/aos/build/download_externals.sh
new file mode 100755
index 0000000..ef843e1
--- /dev/null
+++ b/aos/build/download_externals.sh
@@ -0,0 +1,62 @@
+#!/bin/bash -e
+
+AOS=`dirname $0`/..
+EXTERNALS=${AOS}/externals
+
+# get gccdist
+GCCDIST=${EXTERNALS}/gccdist
+[ -f ${GCCDIST}.zip ] || wget ftp://ftp.ni.com/pub/devzone/tut/updated_vxworks63gccdist.zip -O ${GCCDIST}.zip
+[ -d ${GCCDIST} ] || ( cd ${EXTERNALS} && unzip -q ${GCCDIST}.zip )
+
+# get eigen
+EIGEN_VERSION=3.0.5
+EIGEN_DIR=${EXTERNALS}/eigen-${EIGEN_VERSION}
+[ -f ${EIGEN_DIR}.tar.bz2 ] || wget http://bitbucket.org/eigen/eigen/get/${EIGEN_VERSION}.tar.bz2 -O ${EIGEN_DIR}.tar.bz2
+[ -d ${EIGEN_DIR} ] || ( mkdir ${EIGEN_DIR} && tar --strip-components=1 -C ${EIGEN_DIR} -xf ${EIGEN_DIR}.tar.bz2 )
+
+# get the javacv binaries
+JAVACV_VERSION=0.2
+JAVACV_DIR=${EXTERNALS}/javacv-bin
+JAVACV_ZIP=${EXTERNALS}/javacv-${JAVACV_VERSION}-bin.zip
+[ -f ${JAVACV_ZIP} ] || wget http://javacv.googlecode.com/files/javacv-${JAVACV_VERSION}-bin.zip -O ${JAVACV_ZIP}
+[ -d ${JAVACV_DIR} ] || ( cd ${EXTERNALS} && unzip ${JAVACV_ZIP} )
+
+# get the simple one-jar template jar
+ONEJAR_VERSION=0.97
+ONEJAR_JAR=${EXTERNALS}/one-jar-boot-${ONEJAR_VERSION}.jar
+[ -f ${ONEJAR_JAR} ] || wget http://sourceforge.net/projects/one-jar/files/one-jar/one-jar-${ONEJAR_VERSION}/one-jar-boot-${ONEJAR_VERSION}.jar/download -O ${ONEJAR_JAR}
+
+# get and build libjpeg
+LIBJPEG_VERSION=8d
+LIBJPEG_DIR=${EXTERNALS}/jpeg-${LIBJPEG_VERSION}
+# NOTE: this directory ends up in #include names
+LIBJPEG_PREFIX=${EXTERNALS}/libjpeg
+LIBJPEG_LIB=${LIBJPEG_PREFIX}/lib/libjpeg.a
+LIBJPEG_TAR=${EXTERNALS}/jpegsrc.v${LIBJPEG_VERSION}.tar.gz
+[ -f ${LIBJPEG_TAR} ] || wget http://www.ijg.org/files/jpegsrc.v${LIBJPEG_VERSION}.tar.gz -O ${LIBJPEG_TAR}
+[ -d ${LIBJPEG_DIR} ] || ( mkdir ${LIBJPEG_DIR} && tar --strip-components=1 -C ${LIBJPEG_DIR} -xf ${LIBJPEG_TAR} )
+[ -f ${LIBJPEG_LIB} ] || env -i PATH="${PATH}" bash -c "cd ${LIBJPEG_DIR} && CFLAGS='-m32' ./configure --disable-shared --prefix=`readlink -f ${LIBJPEG_PREFIX}` && make && make install"
+
+# get gtest
+GTEST_VERSION=1.6.0
+GTEST_DIR=${EXTERNALS}/gtest-${GTEST_VERSION}-p1
+GTEST_ZIP=${EXTERNALS}/gtest-${GTEST_VERSION}.zip
+TMPDIR=/tmp/$$-aos-tmpdir
+[ -f ${GTEST_ZIP} ] || wget http://googletest.googlecode.com/files/gtest-${GTEST_VERSION}.zip -O ${GTEST_ZIP}
+[ -d ${GTEST_DIR} ] || ( unzip ${GTEST_ZIP} -d ${TMPDIR} && mv ${TMPDIR}/gtest-${GTEST_VERSION} ${GTEST_DIR} && cd ${GTEST_DIR} && patch -p1 < ../gtest.patch )
+
+# get and build ctemplate
+CTEMPLATE_VERSION=2.2
+CTEMPLATE_DIR=${EXTERNALS}/ctemplate-${CTEMPLATE_VERSION}
+CTEMPLATE_PREFIX=${CTEMPLATE_DIR}-prefix
+CTEMPLATE_LIB=${CTEMPLATE_PREFIX}/lib/libctemplate.a
+CTEMPLATE_URL=http://ctemplate.googlecode.com/files
+CTEMPLATE_URL=${CTEMPLATE_URL}/ctemplate-${CTEMPLATE_VERSION}.tar.gz
+[ -f ${CTEMPLATE_DIR}.tar.gz ] || \
+ wget ${CTEMPLATE_URL} -O ${CTEMPLATE_DIR}.tar.gz
+[ -d ${CTEMPLATE_DIR} ] || ( mkdir ${CTEMPLATE_DIR} && tar \
+ --strip-components=1 -C ${CTEMPLATE_DIR} -xf ${CTEMPLATE_DIR}.tar.gz )
+[ -f ${CTEMPLATE_LIB} ] || env -i PATH="${PATH}" \
+ CFLAGS='-m32' CXXFLAGS='-m32' LDFLAGS='-m32' \
+ bash -c "cd ${CTEMPLATE_DIR} && ./configure --disable-shared \
+ --prefix=`readlink -f ${CTEMPLATE_PREFIX}` && make && make install"
diff --git a/aos/build/externals.gyp b/aos/build/externals.gyp
new file mode 100644
index 0000000..2ed0478
--- /dev/null
+++ b/aos/build/externals.gyp
@@ -0,0 +1,133 @@
+# This file has targets for various external libraries.
+# download_externals.sh makes sure that all of them have been downloaded.
+{
+ 'variables': {
+ 'externals': '<(AOS)/externals',
+ 'externals_abs': '<!(readlink -f ../externals)',
+
+# These versions have to be kept in sync with the ones in download_externals.sh.
+ 'eigen_version': '3.0.5',
+ 'gtest_version': '1.6.0-p1',
+ 'onejar_version': '0.97',
+ 'ctemplate_version': '2.2',
+ },
+ 'targets': [
+ {
+# does nothing when OS!="crio"
+ 'target_name': 'WPILib',
+ 'type': 'none',
+ 'conditions': [['OS=="crio"', {
+ 'direct_dependent_settings': {
+ 'cflags': [
+ '-isystem', '<(aos_abs)/externals/WPILib',
+ ],
+ 'link_settings': {
+ 'libraries': [
+ '<(aos_abs)/externals/WPILib/WPILib.a',
+ ],
+ },
+ },
+ }]],
+ },
+ {
+ 'target_name': 'onejar',
+ 'type': 'none',
+ 'direct_dependent_settings': {
+ 'variables': {
+ 'onejar_jar': '<(externals_abs)/one-jar-boot-<(onejar_version).jar',
+ },
+ },
+ },
+ {
+ 'target_name': 'javacv',
+ 'type': 'none',
+ 'variables': {
+ 'javacv_dir': '<(externals_abs)/javacv-bin',
+ },
+ 'direct_dependent_settings': {
+ 'include_dirs': [
+ '/usr/lib/jvm/default-java/include',
+ '/usr/lib/jvm/default-java/include/linux',
+ ],
+ 'variables': {
+ 'classpath': [
+ '<(javacv_dir)/javacv.jar',
+ '<(javacv_dir)/javacpp.jar',
+ '<(javacv_dir)/javacv-linux-x86.jar',
+ ],
+ },
+ },
+ },
+ {
+# TODO(brians) convert this to downloading + building
+ 'target_name': 'libevent',
+ 'type': 'none',
+ 'link_settings': {
+ 'libraries': ['-levent'],
+ },
+ },
+ {
+ 'target_name': 'eigen',
+ 'type': 'none',
+ 'direct_dependent_settings': {
+ 'include_dirs': ['<(externals)/eigen-<(eigen_version)'],
+ },
+ },
+ {
+ 'target_name': 'libjpeg',
+ 'type': 'none',
+ 'direct_dependent_settings': {
+ 'libraries': ['<(externals_abs)/libjpeg/lib/libjpeg.a'],
+ },
+ },
+ {
+ 'target_name': 'gtest',
+ 'type': 'static_library',
+ 'sources': [
+ '<(externals)/gtest-<(gtest_version)/fused-src/gtest/gtest-all.cc',
+ ],
+ 'conditions': [['OS=="crio"', {
+ 'defines': [
+ 'GTEST_HAS_TR1_TUPLE=0',
+ 'GTEST_HAS_STREAM_REDIRECTION=0',
+ 'GTEST_HAS_POSIX_RE=0', # it only has a broken header...
+ ],
+ 'direct_dependent_settings': {
+ 'defines': [
+ 'GTEST_HAS_TR1_TUPLE=0',
+ 'GTEST_HAS_STREAM_REDIRECTION=0',
+ 'GTEST_HAS_POSIX_RE=0',
+ ],
+ },
+ }, {
+ 'sources': [
+ '<(externals)/gtest-<(gtest_version)/fused-src/gtest/gtest_main.cc',
+ ],
+ }]],
+ 'include_dirs': [
+ '<(externals)/gtest-<(gtest_version)',
+ '<(externals)/gtest-<(gtest_version)/include'
+ ],
+ 'cflags!': ['-Werror'],
+ 'direct_dependent_settings': {
+ 'include_dirs': ['<(externals)/gtest-<(gtest_version)/include'],
+ 'target_conditions': [
+ ['_type=="executable"', {
+ 'product_dir': '<(test_dir)',
+ },
+ ],
+ ],
+ },
+ },
+ {
+ 'target_name': 'ctemplate',
+ 'type': 'none',
+ 'link_settings': {
+ 'libraries': ['<(externals)/ctemplate-<(ctemplate_version)-prefix/lib/libctemplate.a'],
+ },
+ 'direct_dependent_settings': {
+ 'include_dirs': ['<(externals)/ctemplate-<(ctemplate_version)-prefix/include'],
+ },
+ },
+ ],
+}
diff --git a/aos/build/gen_resource_list.rb b/aos/build/gen_resource_list.rb
new file mode 100644
index 0000000..259b438
--- /dev/null
+++ b/aos/build/gen_resource_list.rb
@@ -0,0 +1,36 @@
+outpath = ARGV.shift
+
+outputh = File.new(outpath + '/ResourceList.h', 'w+')
+
+File.open(File.dirname(__FILE__) + '/../atom_code/ipc_lib/resource_list.txt') do |f|
+ outputh.puts <<END
+#ifndef __AOS_RESOURCE_LIST_H_
+#define __AOS_RESOURCE_LIST_H_
+// This file is autogenerated.
+// Edit #{File.expand_path f.path} to change its contents.
+
+#include <stdint.h>
+
+#ifdef __cplusplus // for the c code that just wants to know how long it should be
+namespace aos {
+END
+
+ i = 0
+ f.readlines.each do |l|
+ l = l.chomp
+ outputh.puts "static const uint16_t #{l}(#{i});"
+ i += 1
+ end
+ outputh.puts <<END
+} // namespace aos
+#endif
+
+#define AOS_RESOURCE_NUM #{i}
+
+#endif
+
+END
+end
+
+outputh.close
+
diff --git a/aos/build/java.gypi b/aos/build/java.gypi
new file mode 100644
index 0000000..d832b0a
--- /dev/null
+++ b/aos/build/java.gypi
@@ -0,0 +1,74 @@
+# Include this file in any target that is going to build java files.
+#
+# To use, create a target of the following form:
+# {
+# 'target_name': 'whatever',
+# 'variables': {
+# 'srcdirs': ['.', 'java'],
+# },
+# 'includes': ['path/to/java.gypi'],
+# }
+# See below for more variables.
+# To make any output jars include some loadable modules, set the 'jni_libs'
+# variable in 'direct_dependent_settings'. Making this easier causes lots of
+# recursion issues in gyp.
+# The dependency on these targets also has to be added manually.
+{
+ 'type': 'none',
+ 'variables': {
+# The manifest file for creating the jar.
+ 'manifest%': '/dev/null',
+# Additional jars/directories to add to the classpath when compiling.
+# This target will automatically add itself to this list for any dependents.
+ 'classpath': [],
+# Classes to generate JNI headers for.
+# They will be able to be #included as "jni/package_ClassName.h" by targets
+# that depend on this one.
+ 'gen_headers': [],
+# Like 'srcdirs', except not required to exist at gyp time. However, nothing
+# here will depend on any files in these directories.
+ 'gen_srcdirs': ['/dev/null'],
+# Like 'gen_srcdirs', except all folders that are children of this folder will
+# be used instead.
+ 'gen_srcdir_parents%': [],
+ 'srcdirs': ['/dev/null'],
+ 'jar_dir': '<(PRODUCT_DIR)/jars',
+ 'java_files': '<!(find <(srcdirs) -name *.java)',
+ 'create_jar': '<(AOS)/build/create_jar',
+ 'out_jar': '<(jar_dir)/<(_target_name).jar',
+ 'header_dir': '<(SHARED_INTERMEDIATE_DIR)/jni_headers_<!(pwd | sed s:/:_:g)_<(_target_name)',
+ 'no_rsync': 1,
+ },
+ 'direct_dependent_settings': {
+ 'variables': {
+ 'classpath': ['<(out_jar)'],
+ },
+ 'include_dirs': [
+ '<(header_dir)',
+ ],
+ },
+ 'actions': [
+ {
+ 'action_name': 'run javac',
+ 'message': 'Compiling java code',
+ 'inputs': [
+ '<(create_jar)',
+ '<@(java_files)',
+ '>@(classpath)',
+ '>@(gen_srcdirs)',
+ '>(manifest)',
+ ],
+ 'outputs': [
+ '<(out_jar)',
+ ],
+ 'action': [
+ '<(create_jar)',
+ '<(srcdirs) <(gen_srcdirs)',
+ '<(INTERMEDIATE_DIR)', '>(classpath)',
+ '>(gen_srcdir_parents)',
+ '>(manifest)', '<(out_jar)',
+ '<(header_dir)/jni', '>(gen_headers)',
+ ],
+ },
+ ],
+}
diff --git a/aos/build/jdk_tools_common b/aos/build/jdk_tools_common
new file mode 100644
index 0000000..3ebfc2f
--- /dev/null
+++ b/aos/build/jdk_tools_common
@@ -0,0 +1,13 @@
+# This file gets sourced by all the shell scripts that use the JDK tools.
+# gyp likes quoting some of the input arguments, but nothing else tolerates it,
+# so " are removed from various inputs.
+
+set -e # stop on error
+#set -x # echo everything
+
+TMPDIR=$2
+# ${CLASSPATH} is used by the jdk tools
+EXTRA_CLASSPATH=`echo $3 | tr -d '"' | sed 's/ /:/g'`
+EXTRA_JARS=`echo $3 | tr -d '"'`
+
+mkdir -p ${TMPDIR}
diff --git a/aos/build/mkdirswig b/aos/build/mkdirswig
new file mode 100755
index 0000000..83403e4
--- /dev/null
+++ b/aos/build/mkdirswig
@@ -0,0 +1,7 @@
+#!/bin/bash
+
+# Creates the directory specified by the first argument and runs swig with the
+# rest of the arguments.
+mkdir -p $1
+shift
+swig $@
diff --git a/aos/build/onejar.gypi b/aos/build/onejar.gypi
new file mode 100644
index 0000000..6185f02
--- /dev/null
+++ b/aos/build/onejar.gypi
@@ -0,0 +1,53 @@
+# Include this file in any target that should get packaged with OneJAR.
+#
+# To use, create a target of the following form:
+# {
+# 'target_name': 'whatever',
+# 'variables': {
+# 'main_jar': 'something',
+# },
+# 'includes': ['path/to/onejar.gypi'],
+# },
+# See below for more variables.
+{
+ 'type': 'none',
+ 'variables': {
+# The names of loadable_module targets to add to the jar.
+ 'jni_libs': [],
+# Additional jars to add to the output.
+# Named this so that targets from java.gypi will add themselves automatically.
+ 'classpath': [],
+ 'jar_dir': '<(PRODUCT_DIR)/jars',
+ 'create_onejar': '<(AOS)/build/create_onejar',
+ 'out_onejar': '<(rsync_dir)/<(_target_name).jar',
+ 'main_jar_file': '<(jar_dir)/<(main_jar).jar',
+ 'shared_objects': ">!(echo '>(jni_libs)' | sed 's:[^ ]*:<(so_dir)/lib\\0.so:g')",
+ 'no_rsync': 1,
+ },
+ 'dependencies': [
+ '<(EXTERNALS):onejar',
+ ],
+ 'product_dir': '<(PRODUCT_DIR)',
+ 'actions': [
+ {
+ 'action_name': 'create onejar',
+ 'message': 'Creating OneJAR jar',
+ 'inputs': [
+ '<(create_onejar)',
+ '>@(classpath)',
+ '<(main_jar_file)',
+ '>@(shared_objects)',
+ ],
+ 'outputs': [
+ '<(out_onejar)',
+ ],
+ 'action': [
+ '<(create_onejar)',
+ '<(main_jar_file)',
+ '<(INTERMEDIATE_DIR)', '>(classpath)',
+ '<(out_onejar)', '>(onejar_jar)',
+ '>(shared_objects)',
+ ],
+ },
+ ],
+}
diff --git a/aos/build/parser.rb b/aos/build/parser.rb
new file mode 100644
index 0000000..6163129
--- /dev/null
+++ b/aos/build/parser.rb
@@ -0,0 +1,556 @@
+require 'digest'
+require 'fileutils'
+
+def javaify name
+ name = name.dup
+ name.gsub! /(\w)_(\w)/ do
+ $1 + $2.upcase
+ end
+ name.gsub /^\w/ do |char|
+ char.downcase
+ end
+end
+
+module Contents
+ class SyntaxError < Exception
+ end
+ class Tokenizer
+ def initialize file
+ @file = file
+ @token = ""
+ @lineno = 0
+ end
+ def filename
+ @file.path
+ end
+ def pop_char
+ if char = @hold_char
+ @hold_char = nil
+ return char
+ end
+ return @file.read(1)
+ end
+ def unpop_char char
+ @hold_char = char
+ end
+ def clear_comment
+ @hold_char = nil
+ @file.gets
+ @lineno += 1
+ end
+ def syntax_error error
+ filename = File.basename(@file.path)
+ line = @lineno + 1
+ raise SyntaxError, error + "\n from #{line} of #{filename}", caller
+ end
+ def item_missing item
+ syntax_error "expected \"#{item}\"! you missing something!?"
+ end
+ def peek_token
+ @peek_token = next_token
+ end
+ def next_token
+ if token = @peek_token
+ @peek_token = nil
+ return token
+ end
+ token = @token
+ while char = pop_char
+ if char == "\n"
+ @lineno += 1
+ end
+ if char == "/"
+ if pop_char == "/"
+ clear_comment
+ else
+ syntax_error("unexpected #{char.inspect}")
+ end
+ elsif char =~ /[\s\r\n]/
+ if token.length > 0
+ @token = ""
+ return token
+ end
+ elsif char =~ /[;\{\}]/
+ if token.length > 0
+ unpop_char char
+ @token = ""
+ return token
+ end
+ return(char)
+ elsif token.length > 0 && char =~ /[\w:]/
+ token += char
+ elsif char =~ /[a-zA-Z0-9]/
+ token = char
+ else
+ syntax_error("unexpected #{char.inspect}")
+ end
+ end
+ rescue EOFError
+ end
+ def self.is_string token
+ token =~ /[a-zA-Z]\w*/
+ end
+ def self.is_number token
+ token =~ /[0-9]*/
+ end
+ end
+
+ class Struct
+ class StructField
+ def initialize
+ @members = [] # array of strings
+ end
+ def parse tokenizer
+ while true
+ token = tokenizer.next_token
+ if Tokenizer.is_string(token)
+ @members.push token
+ elsif token == ";" || token == "\n"
+ if @members.length > 0
+ return @members
+ else
+ return nil
+ end
+ else
+ tokenizer.syntax_error("expected member name in struct!")
+ end
+ end
+ end
+ def self.parse *args
+ self.new.parse *args
+ end
+ def use members
+ members
+ end
+ def self.use *args
+ self.new.use *args
+ end
+ def to_s
+ @members.join " "
+ end
+ end
+
+ def parse tokenizer, parse_name = true
+ if parse_name
+ token = tokenizer.next_token
+ if Tokenizer.is_string(token)
+ @name_raw = token
+ else
+ tokenizer.syntax_error("expected struct name!")
+ end
+ else
+ @name_raw = nil
+ @name_data = tokenizer.filename
+ end
+ token = tokenizer.next_token
+ tokenizer.syntax_error("expected '{', got '#{token}'") if(token != "{")
+ while token != "}"
+ token = tokenizer.peek_token
+ if token != "}"
+ field = StructField.parse(tokenizer)
+ @fields.push(field) if(field)
+ end
+ end
+ if tokenizer.next_token == "}"
+ return self
+ else
+ tokenizer.syntax_error("wahh; call parker. #{__LINE__}")
+ end
+ end
+ def self.parse *args
+ self.new.parse *args
+ end
+
+ def use fields, name_data
+ @name_raw = nil
+ @name_data = name_data
+ fields.each do |field|
+ @fields.push(StructField.use field.split(' '))
+ end
+ self
+ end
+ def self.use *args
+ self.new.use *args
+ end
+
+ def name
+ @name_raw || gen_name
+ end
+ def gen_name
+ unless @generated_name
+ @generated_name = 'a' + Digest::SHA1.hexdigest(@fields.join('') + $namespace + @name_data)
+ end
+ @generated_name
+ end
+
+ def initialize
+ @fields = [] # array of arrays of strings
+ @hidden_fields = []
+ end
+ def upcase_name
+ name.gsub(/^[a-z]|_[a-z]/) do |v|
+ v[-1].chr.upcase
+ end
+ end
+ def join_fields array
+ (array.collect { |a|
+ " #{a.join(" ")};"
+ }).join("\n")
+ end
+ def fields
+ join_fields @fields
+ end
+ def hidden_fields
+ join_fields @hidden_fields
+ end
+ def add_hidden_field k, v
+ @hidden_fields.push [k, v]
+ end
+ def params
+ (@fields.collect do |a|
+ a.join(" ")
+ end).join(', ')
+ end
+ def copy_params_into varname, decl = true
+ (decl ? "#{name} #{varname};\n" : '') + (@fields.collect do |a|
+ "#{varname}.#{a[-1]} = #{a[-1]};"
+ end).join("\n")
+ end
+ def params_from name
+ (@fields.collect do |a|
+ name + '.' + a[-1]
+ end).join(', ')
+ end
+ def builder_name aos_namespace = true, this_namespace = true
+ (aos_namespace ? "aos::" : '') + "QueueBuilder<#{this_namespace ? $namespace + '::' : ''}#{name}>"
+ end
+ def java_builder
+ name + 'Builder'
+ end
+ def builder_defs name
+ (@fields.collect do |field|
+ " inline #{name} &#{field[-1]}" +
+ "(#{field[0...-1].join(" ")} in) " +
+ "{ holder_.View().#{field[-1]} = in; return *this; }"
+ end).join "\n"
+ end
+ def swig_builder_defs name
+ (@fields.collect do |field|
+ " %rename(#{javaify field[-1]}) #{field[-1]};\n" +
+ " #{name} &#{field[-1]}" +
+ "(#{field[0...-1].join(" ")} #{field[-1]});"
+ end).join "\n"
+ end
+ def zero name
+ (@fields.collect do |field|
+ " new (&#{name}.#{field[-1]}) #{field[0...-1].join ' '}();"
+ end).join("\n")
+ end
+ def size
+ (@fields.collect do |field|
+ "sizeof(#{$namespace}::#{name}::#{field[-1]})"
+ end.push('0')).join(' + ')
+ end
+ def get_format(field)
+ case(field[0...-1])
+ when ['int']
+ r = '%d'
+ when ['float'], ['double']
+ r = '%f'
+ when ['bool']
+ r = '%s'
+ when ['uint8_t']
+ r = '%hhu'
+ when ['uint16_t']
+ r = '%d'
+ when ['struct', 'timespec']
+ r = '%jdsec,%ldnsec'
+ else
+ return 'generator_error'
+ end
+ return field[-1] + ': ' + r
+ end
+ def to_printf(name, field)
+ case(field[0...-1])
+ when ['bool']
+ return name + '.' + field[-1] + ' ? "true" : "false"'
+ when ['uint16_t']
+ return "static_cast<int>(#{name}.#{field[-1]})"
+ when ['struct', 'timespec']
+ return "#{name}.#{field[-1]}.tv_sec, #{name}.#{field[-1]}.tv_nsec"
+ else
+ return name + '.' + field[-1]
+ end
+ end
+ def netop name, buffer
+ offset = '0'
+ (@fields.collect do |field|
+ # block |var_pointer, output_pointer|
+ val = yield "&#{name}.#{field[-1]}", "&#{buffer}[#{offset}]"
+ offset += " + sizeof(#{name}.#{field[-1]})"
+ ' ' + val
+ end).join("\n") + "\n " +
+ "static_assert(#{offset} == #{size}, \"code generator issues\");"
+ end
+ def hton name, output
+ netop(name, output) do |var, output|
+ "to_network(#{var}, #{output});"
+ end
+ end
+ def ntoh input, name
+ netop(name, input) do |var, input|
+ "to_host(#{input}, #{var});"
+ end
+ end
+ def swig_writer
+ <<END
+struct #{name} {
+#{(@fields.collect { |a|
+ " %rename(#{javaify a[-1]}) #{a[-1]};"
+}).join("\n")}
+#{self.fields}
+ %extend {
+ const char *toString() {
+ return aos::TypeOperator<#{$namespace}::#{name}>::Print(*$self);
+ }
+ }
+ private:
+ #{name}();
+};
+} // namespace #{$namespace}
+namespace aos {
+%typemap(jstype) #{builder_name false}& "#{java_builder}"
+%typemap(javaout) #{builder_name false}& {
+ $jnicall;
+ return this;
+ }
+template <> class #{builder_name false} {
+ private:
+ #{builder_name false}();
+ public:
+ inline bool Send();
+ %rename(#{javaify 'Send'}) Send;
+#{swig_builder_defs builder_name(false)}
+};
+%template(#{java_builder}) #{builder_name false};
+%typemap(javaout) #{builder_name false}& {
+ return new #{java_builder}($jnicall, false);
+ }
+} // namespace aos
+namespace #{$namespace} {
+END
+ end
+ def writer
+ <<END
+struct #{name} {
+#{self.fields}
+#{self.hidden_fields}
+};
+} // namespace #{$namespace}
+namespace aos {
+template <> class TypeOperator<#{$namespace}::#{name}> {
+ public:
+ static void Zero(#{$namespace}::#{name} &inst) {
+ (void)inst;
+#{zero 'inst'}
+ }
+ static void NToH(const char *input, #{$namespace}::#{name} &inst) {
+ (void)input;
+ (void)inst;
+#{ntoh 'input', 'inst'}
+ }
+ static void HToN(const #{$namespace}::#{name} &inst, char *output) {
+ (void)inst;
+ (void)output;
+#{hton 'inst', 'output'}
+ }
+ static inline size_t Size() { return #{size}; }
+ static const char *Print(const #{$namespace}::#{name} &inst) {
+#{@fields.empty? ? <<EMPTYEND : <<NOTEMPTYEND}
+ (void)inst;
+ return "";
+EMPTYEND
+ static char buf[1024];
+ if (snprintf(buf, sizeof(buf), "#{@fields.collect do |field|
+ get_format(field)
+ end.join(', ')}", #{@fields.collect do |field|
+ to_printf('inst', field)
+ end.join(', ')}) >= static_cast<ssize_t>(sizeof(buf))) {
+ LOG(WARNING, "#{name}'s buffer was too small\\n");
+ buf[sizeof(buf) - 1] = '\\0';
+ }
+ return buf;
+NOTEMPTYEND
+ }
+};
+template <> class #{builder_name false} {
+ private:
+ aos::QueueHolder<#{$namespace}::#{name}> &holder_;
+ public:
+ #{builder_name false}(aos::QueueHolder<#{$namespace}::#{name}> &holder) : holder_(holder) {}
+ inline bool Send() { return holder_.Send(); }
+ inline const char *Print() const { return holder_.Print(); }
+#{builder_defs builder_name(false)}
+};
+} // namespace aos
+namespace #{$namespace} {
+END
+ end
+ def to_s
+ return <<END
+#{name}: #{(@fields.collect {|n| n.join(" ") }).join("\n\t")}
+END
+ end
+ end
+
+ class SimpleField
+ def initialize check_function = :is_string
+ @check_function = check_function
+ @name = nil
+ end
+ def parse tokenizer
+ token = tokenizer.next_token
+ if Tokenizer.__send__ @check_function, token
+ @name = token
+ else
+ tokenizer.syntax_error('expected value!')
+ end
+ if tokenizer.next_token == ';'
+ @name
+ else
+ tokenizer.syntax_error('expected ";"!')
+ end
+ end
+ def self.parse tokenizer
+ self.new.parse tokenizer
+ end
+ end
+ class NameField < SimpleField
+ end
+
+ class OutputFile
+ def initialize namespace, filename, topdir, outpath
+ @namespace = namespace
+ $namespace = namespace
+ @base = filename.gsub(/\.\w*$/, "").gsub(/^.*\//, '')
+ @topdir = topdir
+ @filebase = outpath + @base
+ @filename = filename
+ FileUtils.mkdir_p(outpath)
+
+ fillin_initials if respond_to? :fillin_initials
+ parse filename
+ fillin_defaults if respond_to? :fillin_defaults
+ self
+ rescue SyntaxError => e
+ puts e
+ exit 1
+ end
+ def filename type
+ case type
+ when 'h'
+ @filebase + '.q.h'
+ when 'cc'
+ @filebase + '.q.cc'
+ when 'main'
+ @filebase + '_main.cc'
+ when 'swig'
+ @filebase + '.swg'
+ when 'java_dir'
+ @filebase + '_java/'
+ when 'java_wrap'
+ @filebase + '_java_wrap.cc'
+ else
+ throw SyntaxError, "unknown filetype '#{type}'"
+ end
+ end
+ def parse filename
+ file = File.open filename
+ tokenizer = Tokenizer.new file
+ while token = tokenizer.next_token
+ if !token || token.gsub('\s', '').empty?
+ elsif token == ';'
+ else
+ error = catch :syntax_error do
+ case token
+ when 'namespace'
+ $namespace = NameField.parse tokenizer
+ else
+ parse_token token, tokenizer
+ end
+ nil
+ end
+ if error
+ tokenizer.syntax_error error.to_s
+ raise error
+ end
+ end
+ end
+
+ check_format tokenizer
+ end
+ def call_swig
+ output_dir = filename('java_dir') + $namespace
+ FileUtils.mkdir_p(output_dir)
+ if (!system('swig', '-c++', '-Wall', '-Wextra', '-java',
+ '-package', $namespace, "-I#{@topdir}",
+ '-o', filename('java_wrap'),
+ '-outdir', output_dir, filename('swig')))
+ exit $?.to_i
+ end
+ end
+
+ def queue_holder_accessors suffix, var, type, force_timing = nil
+<<END
+ inline bool Get#{suffix}(#{force_timing ? '' : 'bool check_time'}) aos_check_rv { return #{var}.Get(#{force_timing || 'check_time'}); }
+ inline #{type} &View#{suffix}() { return #{var}.View(); }
+ inline void Clear#{suffix}() { #{var}.Clear(); }
+ inline bool Send#{suffix}() { return #{var}.Send(); }
+ inline const char *Print#{suffix}() { return #{var}.Print(); }
+ inline aos::QueueBuilder<#{type}> &#{suffix || 'Builder'}() { return #{var}.Builder(); }
+END
+ end
+ def queue_holder_accessors_swig suffix, var, type, force_timing = nil
+<<END
+ %rename(#{javaify "Get#{suffix}"}) Get#{suffix};
+ bool Get#{suffix}(#{force_timing ? '' : 'bool check_time'});
+ %rename(#{javaify "View#{suffix}"}) View#{suffix};
+ #{type} &View#{suffix}();
+ %rename(#{javaify "Clear#{suffix}"}) Clear#{suffix};
+ void Clear#{suffix}();
+ %rename(#{javaify "Send#{suffix}"}) Send#{suffix};
+ bool Send#{suffix}();
+ %rename(#{javaify suffix || 'Builder'}) #{suffix || 'Builder'};
+ aos::QueueBuilder<#{type}> &#{suffix || 'Builder'}();
+END
+ end
+ end
+end
+
+def write_file_out
+ if ARGV.length < 3
+ puts 'Error: at least 3 arguments required!!!'
+ exit 1
+ end
+ file = Contents::OutputFile.new ARGV.shift,
+ File.expand_path(ARGV.shift),
+ ARGV.shift,
+ File.expand_path(ARGV.shift) + '/'
+ while !ARGV.empty?
+ case type = ARGV.shift
+ when 'cpp'
+ file.write_cpp
+ when 'header'
+ file.write_header
+ when 'main'
+ file.write_main
+ when 'swig'
+ file.write_swig
+ file.call_swig
+ else
+ puts "Error: unknown output type '#{type}'"
+ exit 1
+ end
+ end
+end
+
diff --git a/aos/build/queues.gypi b/aos/build/queues.gypi
new file mode 100644
index 0000000..30fe7cd
--- /dev/null
+++ b/aos/build/queues.gypi
@@ -0,0 +1,123 @@
+# Include this file in any target that needs to use files generated from queue
+# etc. definitions.
+#
+# To use, create a target of the following form:
+# {
+# 'target_name': 'my_queues',
+# 'type': 'static_library', # or any other type that can handle .cc files
+# 'sources': [
+# 'aos/example/Queue.q',
+# 'aos/example/ControlLoop.q',
+# ],
+# 'variables': {
+# 'header_path': 'aos/example',
+# },
+# 'includes': ['path/to/queues.gypi'],
+# },
+# Code that depends on this target will be able to #include
+# "aos/example/Queue.q.h" and "aos/example/ControlLoop.q.h".
+#
+# using <http://src.chromium.org/svn/trunk/src/build/protoc.gypi> as an
+# example of how this should work
+{
+ 'variables': {
+ #'header_path': '>!(python -c "import os.path; print os.path.relpath(\'<(RULE_INPUT_PATH)\', \'<(DEPTH)\')")',
+ 'prefix_dir': '<(SHARED_INTERMEDIATE_DIR)/<!(echo <(header_path) | sed "s/[^A-Za-z0-9]/_/g")',
+ 'out_dir': '<(prefix_dir)/<(_target_name)/<(header_path)',
+ 'gen_namespace%': '>!(echo >(header_path) | sed "s:\([^/]*\).*:\\1:g")',
+ 'output_h': '<(out_dir)/<(RULE_INPUT_ROOT).q.h',
+ 'output_cc': '<(out_dir)/<(RULE_INPUT_ROOT).q.cc',
+ 'output_main': '<(out_dir)/<(RULE_INPUT_ROOT)_main.cc',
+ 'output_swg': '<(out_dir)/<(RULE_INPUT_ROOT).q.swig',
+ 'output_java_wrap': '<(out_dir)/<(RULE_INPUT_ROOT)_java_wrap.cc',
+ 'java_dir': '<(out_dir)/<(RULE_INPUT_ROOT).q_java',
+ 'no_rsync': 1,
+ },
+ 'rules': [
+ {
+ 'variables': {
+ 'script': '<(AOS)/build/queues/compiler.rb',
+ },
+ 'rule_name': 'genqueue',
+ 'extension': 'q',
+ 'outputs': [
+ '<(output_h)',
+ '<(output_cc)',
+ ],
+ 'conditions': [
+ ['OS=="crio"', {
+ 'outputs': [
+ # cRIO doesn't do swig for a good reason.
+ ]
+ },{
+ 'outputs': [
+ '<(output_swg)',
+ '<(output_java_wrap)',
+ '<(java_dir)',
+ ]
+ }]
+ ],
+ 'inputs': [
+ '<(script)',
+ '<!@(find <(AOS)/build/queues/ -name *.rb)',
+ '<(AOS)/common/queue.h',
+ '<(AOS)/common/time.h',
+ ],
+ 'action': ['ruby', '<(script)',
+ '--swig',
+ '--swigccout', '<(output_java_wrap)',
+ '-I', '<(DEPTH)',
+ '<(RULE_INPUT_PATH)',
+ '-cpp_out',
+ '<(header_path)',
+ '-cpp_base',
+ '<(prefix_dir)/<(_target_name)'],
+ 'message': 'Generating C++ code from <(RULE_INPUT_DIRNAME)/<(RULE_INPUT_ROOT).q',
+ 'process_outputs_as_sources': 1,
+ },
+ {
+ 'variables': {
+ 'script': '<(AOS)/build/act_builder.rb',
+ },
+ 'rule_name': 'genact',
+ 'extension': 'act',
+ 'outputs': [
+ '<(output_h)',
+ '<(output_cc)',
+ '<(output_main)',
+ ],
+ 'inputs': [
+ '<(script)',
+ ],
+ 'action': ['ruby', '<(script)',
+ '<(gen_namespace)',
+ '<(RULE_INPUT_PATH)',
+ '<(DEPTH)',
+ '<(out_dir)', 'header', 'cpp', 'main'],
+ #'message': 'Generating C++ code from <(RULE_INPUT_DIRNAME)/<(RULE_INPUT_ROOT).act',
+ 'process_outputs_as_sources': 1,
+ },
+ ],
+ 'cflags': [
+# For the swig-generated C++ code.
+ '-fno-strict-aliasing',
+ '-Wno-cast-qual',
+ ],
+ 'include_dirs': [
+ '/usr/lib/jvm/default-java/include',
+ '/usr/lib/jvm/default-java/include/linux',
+ '<(prefix_dir)/<(_target_name)',
+ ],
+ 'direct_dependent_settings': {
+ 'include_dirs': [
+ '<(prefix_dir)/<(_target_name)',
+ ],
+ 'variables': {
+ 'gen_srcdir_parents': ['<(out_dir)'],
+ },
+ },
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:aos_internal_nolib',
+ ],
+ 'hard_dependency': 1,
+}
diff --git a/aos/build/queues/compiler.rb b/aos/build/queues/compiler.rb
new file mode 100644
index 0000000..aef5cbf
--- /dev/null
+++ b/aos/build/queues/compiler.rb
@@ -0,0 +1,151 @@
+["tokenizer.rb","q_file.rb","queue_group.rb","queue.rb","namespaces.rb",
+"interface.rb","errors.rb"].each do |name|
+ require File.dirname(__FILE__) + "/objects/" + name
+end
+["standard_types.rb","auto_gen.rb","file_pair_types.rb",
+"dep_file_pair.rb","swig.rb"].each do |name|
+ require File.dirname(__FILE__) + "/cpp_pretty_print/" + name
+end
+["q_file.rb","message_dec.rb","queue_dec.rb"].each do |name|
+ require File.dirname(__FILE__) + "/output/" + name
+end
+require "fileutils"
+require "pathname"
+
+def parse_args(globals,args)
+ i = 0
+ $swig = false
+ $swigccout_path = ""
+ while(i < args.length)
+ if(args[i] == "-I")
+ args.delete_at(i)
+ if(!args[i])
+ $stderr.puts "hey! -I is followed by nothing."
+ $stderr.puts "\tnot a supported usage..."
+ $stderr.puts "\tWot. Wot."
+ exit!(-1)
+ end
+ path = args.delete_at(i)
+ globals.add_path(path)
+ elsif(args[i] == "--swigccout")
+ args.delete_at(i)
+ $swigccout_path = args.delete_at(i)
+ elsif(args[i] == "-cpp_out")
+ args.delete_at(i)
+ path = args.delete_at(i)
+ if(path =~ /\./)
+ $stderr.puts "hey! path #{path} has a \".\" char which is "
+ $stderr.puts "\tnot a supported usage..."
+ $stderr.puts "\tWot. Wot."
+ exit!(-1)
+ elsif(!path)
+ $stderr.puts "hey! No cpp_out path provided."
+ $stderr.puts "\tumm, you could try -cpp_out \"\""
+ $stderr.puts "\tThat might do the trick"
+ $stderr.puts "\tWot. Wot."
+ exit!(-1)
+ end
+ $cpp_out = path.split(/\\|\//)
+ elsif(args[i] == "--swig")
+ $swig = true
+ args.delete_at(i)
+ elsif(args[i] == "-cpp_base")
+ args.delete_at(i)
+ path = args.delete_at(i)
+ $cpp_base = File.expand_path(path)
+ if(!File.exists?($cpp_base))
+ $stderr.puts "output directory #{$cpp_base.inspect} does not exist."
+ $stderr.puts "\tI'm not going to make that! sheesh, who do you think I am?"
+ $stderr.puts "\tWot. Wot."
+ exit!(-1)
+ end
+ elsif(args[i] =~ /^-/)
+ $stderr.puts "hey! unknown argument #{args[i]}."
+ $stderr.puts "\tWot. Wot."
+ exit!(-1)
+ else
+ i += 1
+ end
+ end
+ if(!$cpp_base)
+ $stderr.puts "hey! missing -cpp_base argument."
+ $stderr.puts "\tWot. Wot."
+ exit!(-1)
+ end
+ if(!$cpp_out)
+ $stderr.puts "hey! missing -cpp_out argument."
+ $stderr.puts "\tWot. Wot."
+ exit!(-1)
+ end
+end
+def build(filename,globals_template)
+ globals = Globals.new()
+ globals_template.paths.each do |path|
+ globals.add_path(path)
+ end
+ filename = File.expand_path(filename)
+ q_file = QFile.parse(filename)
+ output_file = q_file.q_eval(globals)
+ q_filename = File.basename(filename)
+ rel_path = ($cpp_out + [q_filename]).join("/")
+
+ FileUtils.mkdir_p(Pathname.new($cpp_base) + $cpp_out.join("/"))
+
+ cpp_tree = output_file.make_cpp_tree(rel_path)
+
+ h_file_path = $cpp_base + "/" + rel_path + ".h"
+ cc_file_path = $cpp_base + "/" + rel_path + ".cc"
+ swig_file_path = $cpp_base + "/" + rel_path + ".swig"
+ java_directory = $cpp_base + "/" + rel_path + "_java/"
+ cpp_tree.add_cc_include((rel_path + ".h").inspect)
+ cpp_tree.add_cc_include("aos/common/byteorder.h".inspect)
+ cpp_tree.add_cc_include("aos/common/inttypes.h".inspect)
+ cpp_tree.add_cc_using("::aos::to_network")
+ cpp_tree.add_cc_using("::aos::to_host")
+ cpp_tree.add_swig_header_include("aos/common/queue.h".inspect)
+ cpp_tree.add_swig_body_include("aos/atom_code/queue-tmpl.h".inspect)
+ cpp_tree.add_swig_header_include("aos/common/time.h".inspect)
+ cpp_tree.add_swig_include((rel_path + ".h").inspect)
+
+ header_file = File.open(h_file_path,"w+")
+ cc_file = File.open(cc_file_path,"w+")
+ cpp_tree.write_header_file($cpp_base,header_file)
+ cpp_tree.write_cc_file($cpp_base,cc_file)
+ cc_file.close()
+ header_file.close()
+ if ($swig)
+ swig_file = File.open(swig_file_path,"w+")
+ cpp_tree.write_swig_file($cpp_base,swig_file,q_filename)
+ swig_file.close()
+ namespace = q_file.namespace.get_name()[1..-1]
+ FileUtils.mkdir_p(java_directory)
+ includes = globals.paths.collect { |a| "-I#{a}" }
+
+ if (!system('/usr/bin/swig', *(includes + ['-I' + $cpp_base + '/',
+ '-package', namespace,
+ '-outdir', java_directory,
+ '-o', $swigccout_path,
+ '-c++', '-Wall', '-Wextra', '-java', swig_file_path])))
+ puts "Swig failed."
+ exit -1
+ end
+ end
+end
+begin
+ args = ARGV.dup
+ globals = Globals.new()
+ parse_args(globals,args)
+ if(args.length == 0)
+ $stderr.puts "hey! you want me to do something,"
+ $stderr.puts "\tbut you gave me no q files to build!"
+ $stderr.puts "\tWot. Wot."
+ exit!(-1)
+ end
+ args.each do |filename|
+ build(filename,globals)
+ end
+ exit(0)
+rescue QError => e
+ $stderr.print(e.to_s)
+ exit!(-1)
+end
diff --git a/aos/build/queues/cpp_pretty_print/auto_gen.rb b/aos/build/queues/cpp_pretty_print/auto_gen.rb
new file mode 100644
index 0000000..633c7c0
--- /dev/null
+++ b/aos/build/queues/cpp_pretty_print/auto_gen.rb
@@ -0,0 +1,282 @@
+module CPP
+end
+class CPP::Comment
+ def initialize(text)
+ @text = text
+ end
+ def pp(state)
+ state.needs_semi = false
+ if(@text.include?("\n"))
+ state.print("/* #{@text} */")
+ else
+ state.print("// #{@text}")
+ end
+ end
+end
+class CPP::TODO < CPP::Comment
+ def initialize(owner,text)
+ @text = "TODO(#{owner}): #{text}"
+ end
+end
+class CPP::MemberFunc
+ class ForwardDec
+ def initialize(func) ; @func = func ; end
+ def pp(state) ; @func.pp_forward_dec(state) ; end
+ end
+ attr_accessor :args,:suite,:return_type,:name,:pre_func_types,:const,:static,:virtual
+ def initialize(type_class,return_type,name)
+ @type_class = type_class
+ @return_type = return_type
+ @name = name
+ @const = false
+ @static = false
+ @virtual = false
+ @args = CPP::Args.new()
+ @suite = CPP::Suite.new()
+ end
+ attr_accessor :inline
+ def forward_dec() ; ForwardDec.new(self) ; end
+ def pp_forward_dec(state)
+ return self.pp_inline(state) if(@inline)
+ if (@static)
+ state.print("static ")
+ elsif (@virtual)
+ state.print("virtual ")
+ end
+ state.print("#{@return_type} #{@pre_func_types}#{@name}(")
+ state.pp(@args)
+ state.print(")")
+ if (@const)
+ state.print(" const")
+ end
+ end
+ def pp_inline(state)
+ if (@static)
+ state.print("static ")
+ elsif (@virtual)
+ state.print("virtual ")
+ end
+ state.print("#{@return_type} #{@pre_func_types}#{@name}(")
+ state.pp(@args)
+ state.print(") ")
+ if (@const)
+ state.print(" const")
+ end
+ @suite.pp_one_line(state)
+ end
+ def pp(state)
+ return if(@inline)
+ state.print("#{@return_type} #{@pre_func_types}#{@type_class.chop_method_prefix}#{@name}(")
+ state.pp(@args)
+ state.print(") ")
+ if (@const)
+ state.print("const ")
+ end
+ state.pp(@suite)
+ state.v_pad(2)
+ end
+ def pp_pre_swig_file(state)
+ end
+ def pp_post_swig_file(state)
+ end
+ alias_method :pp_header_file, :pp_forward_dec
+ alias_method :pp_cc_file, :pp
+
+end
+class CPP::Constructor
+ class ForwardDec
+ def initialize(func) ; @func = func ; end
+ def pp(state) ; @func.pp_forward_dec(state) ; end
+ end
+ attr_accessor :args,:suite,:return_type,:name
+ def initialize(type_class)
+ @type_class = type_class
+ @args = CPP::Args.new()
+ @suite = CPP::Suite.new()
+ @var_cons = CPP::Args.new()
+ end
+ def forward_dec() ; ForwardDec.new(self) ; end
+ def add_cons(*args)
+ @var_cons.push(CPP::FuncCall.build(*args))
+ end
+ def pp_forward_dec(state)
+ state.print("#{@type_class.name}(")
+ state.pp(@args)
+ state.print(")")
+ end
+ def pp_inline(state)
+ pp(state,false)
+ end
+ def pp(state,prefix = true)
+ state.needs_semi = false
+ state.print(@type_class.chop_method_prefix) if(prefix)
+ state.print("#{@type_class.name}(")
+ state.pp(@args)
+ if(@var_cons.length >= 1)
+ state.print(")")
+ state.endline()
+ state.indent += 4
+ state.print(": ")
+ state.pp(@var_cons)
+ state.indent -= 4
+ state.print(" ")
+ else
+ state.print(") ")
+ end
+ state.pp(@suite)
+ state.v_pad(2)
+ end
+ alias_method :pp_header_file, :pp_forward_dec
+ alias_method :pp_cc_file, :pp
+end
+class CPP::Destructor
+ class ForwardDec
+ def initialize(func) ; @func = func ; end
+ def pp(state) ; @func.pp_forward_dec(state) ; end
+ end
+ attr_accessor :args,:suite,:return_type,:name
+ def initialize(type_class)
+ @type_class = type_class
+ @args = CPP::Args.new()
+ @suite = CPP::Suite.new()
+ end
+ def forward_dec() ; ForwardDec.new(self) ; end
+ def pp_forward_dec(state)
+ state.print("~#{@type_class.name}(")
+ state.pp(@args)
+ state.print(")")
+ end
+ def pp(state)
+ state.print("#{@type_class.chop_method_prefix}~#{@type_class.name}(")
+ state.pp(@args)
+ state.print(") ")
+ state.pp(@suite)
+ state.v_pad(2)
+ end
+ alias_method :pp_header_file, :pp_forward_dec
+ alias_method :pp_cc_file, :pp
+end
+class CPP::Include
+ attr_accessor :filename
+ def initialize(filename)
+ @filename = filename
+ end
+ def pp(state)
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("#include #{@filename}")
+ state.endline()
+ end
+end
+class CPP::IncludeGuard
+ attr_accessor :name,:suite
+ def initialize(suite = CPP::Suite.new())
+ @suite = suite
+ end
+ def self.rand_name(len = 40)
+ str = ""
+ len.times { str += ((rand(26) + ?A).chr)}
+ return str
+ end
+ def pp(state)
+ @name ||= IncludeGuard.rand_name
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("#ifndef #{@name}")
+ state.endline()
+ state.suppress_indent()
+ state.print("#define #{@name}")
+ state.endline()
+ if(@suite.respond_to?(:pp_no_braces))
+ @suite.pp_no_braces(state)
+ else
+ state.pp(@suite)
+ end
+ state.endline()
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("#endif // #{@name}")
+ state.endline()
+ end
+end
+class CPP::IfnDef
+ attr_accessor :name,:suite
+ def initialize(suite = CPP::Suite.new())
+ @suite = suite
+ end
+ def pp(state)
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("#ifndef #{@name}")
+ state.endline()
+ if(@suite.respond_to?(:pp_no_braces))
+ @suite.pp_no_braces(state)
+ else
+ state.pp(@suite)
+ end
+ state.endline()
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("#endif // #{@name}")
+ state.endline()
+ end
+end
+class CPP::PreprocessorIf
+ attr_accessor :name,:suite
+ def initialize(ifsuite, elsesuite)
+ @ifsuite = ifsuite
+ @elsesuite = elsesuite
+ end
+ def write_if(state)
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("#if #{@name}")
+ state.endline()
+ end
+ def write_else(state)
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("#else // #{@name}")
+ state.endline()
+ end
+ def write_endif(state)
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("#endif // #{@name}")
+ state.endline()
+ end
+ def pp_inline(state)
+ self.write_if(state)
+ @ifsuite.pp_inline(state)
+ if(@elsesuite != nil)
+ self.write_else(state)
+ @elsesuite.pp_inline(state)
+ end
+ self.write_endif(state)
+ end
+ def pp(state)
+ self.write_if(state)
+ if(@ifsuite.respond_to?(:pp_no_braces))
+ @ifsuite.pp_no_braces(state)
+ else
+ state.pp(@ifsuite)
+ end
+ if(@elsesuite != nil)
+ self.write_else(state)
+ if(@elsesuite.respond_to?(:pp_no_braces))
+ @elsesuite.pp_no_braces(state)
+ else
+ state.pp(@elsesuite)
+ end
+ end
+ self.write_endif(state)
+ end
+end
+class CPP::Using
+ def initialize(using)
+ @using = using
+ end
+ def pp(state)
+ state.print("using #{@using}")
+ end
+end
diff --git a/aos/build/queues/cpp_pretty_print/dep_file_pair.rb b/aos/build/queues/cpp_pretty_print/dep_file_pair.rb
new file mode 100644
index 0000000..571d9e0
--- /dev/null
+++ b/aos/build/queues/cpp_pretty_print/dep_file_pair.rb
@@ -0,0 +1,617 @@
+class GroupElement
+ def add_group_dep(group_dep)
+ @group_dep = group_dep
+ end
+ def adjust_group(state,old_group)
+ if(@group_dep != old_group)
+ @group_dep.adjust_from(state,old_group)
+ end
+ return @group_dep
+ end
+end
+class DepMask < GroupElement
+ def initialize(elem)
+ @elem = elem
+ @deps = []
+ end
+ def add_dep(dep)
+ @deps << dep
+ self
+ end
+ def method_missing(method,*args,&blk)
+ @elem.send(method,*args,&blk)
+ end
+ alias_method :old_respond_to, :respond_to?
+ def respond_to?(method)
+ old_respond_to(method) || @elem.respond_to?(method)
+ end
+end
+
+class MemberElementHeader < GroupElement
+ def initialize(elem)
+ @elem = elem
+ end
+ def pp(state)
+ if(@elem.respond_to?(:pp_header_file))
+ @elem.pp_header_file(state)
+ else
+ state.pp(@elem)
+ end
+ end
+ def self.check(plan,elem)
+ plan.push(self.new(elem))
+ end
+end
+class MemberElementInline < GroupElement
+ def initialize(elem)
+ @elem = elem
+ end
+ def pp(state)
+ if(@elem.respond_to?(:pp_inline))
+ @elem.pp_inline(state)
+ else
+ state.pp(@elem)
+ end
+ end
+end
+class MemberElementPreSWIG < GroupElement
+ def initialize(elem)
+ @elem = elem
+ end
+ def pp(state)
+ if(@elem.respond_to?(:pp_pre_swig_file))
+ @elem.pp_pre_swig_file(state)
+ else
+ state.pp(@elem)
+ end
+ end
+ def self.check(plan,elem)
+ plan.push(self.new(elem)) if(elem.respond_to?(:pp_pre_swig_file))
+ end
+end
+class MemberElementPostSWIG < GroupElement
+ def initialize(elem)
+ @elem = elem
+ end
+ def pp(state)
+ if(@elem.respond_to?(:pp_post_swig_file))
+ @elem.pp_post_swig_file(state)
+ else
+ state.pp(@elem)
+ end
+ end
+ def self.check(plan,elem)
+ plan.push(self.new(elem)) if(elem.respond_to?(:pp_post_swig_file))
+ end
+end
+class MemberElementCC < GroupElement
+ attr_accessor :pp_override
+ def initialize(elem)
+ @elem = elem
+ end
+ def pp(state)
+ return state.pp(@elem) if(@pp_override)
+ @elem.pp_cc_file(state)
+ end
+ def self.check(plan,elem)
+ plan.push(self.new(elem)) if(elem.respond_to?(:pp_cc_file))
+ end
+end
+class ImplicitName
+ attr_accessor :parent
+ def initialize(name,parent)
+ @name = name
+ @parent = parent
+ end
+ def close(state)
+ state.endline()
+ state.needs_semi = false
+ state.print("} // namespace #{@name}\n")
+ end
+ def name()
+ if(@parent)
+ return @parent.name + "." + @name
+ else
+ return "." + @name
+ end
+ end
+ def open(state)
+ state.endline()
+ state.needs_semi = false
+ state.print("namespace #{@name} {\n")
+ end
+ def adjust_from(state,old_group)
+ close_grps = []
+ grp = old_group
+ while(grp)
+ close_grps << grp
+ grp = grp.parent
+ end
+ open_grps = []
+ grp = self
+ while(grp)
+ open_grps << grp
+ grp = grp.parent
+ end
+ while(open_grps[-1] == close_grps[-1] && close_grps[-1])
+ close_grps.pop()
+ open_grps.pop()
+ end
+ close_grps.each do |grp|
+ grp.close(state)
+ end
+ open_grps.reverse.each do |grp|
+ grp.open(state)
+ end
+ end
+ def adjust_to(state,new_group)
+ grp = self
+ while(grp)
+ grp.close(state)
+ grp = grp.parent
+ end
+ end
+end
+class GroupPlan < GroupElement
+ attr_accessor :implicit
+ def initialize(group_elem,members = [])
+ @group_elem = group_elem
+ @members = CPP::Suite.new(members)
+ end
+ def push(mem)
+ mem.add_group_dep(@implicit) if(@implicit)
+ @members << mem
+ end
+ def pp(state)
+ if(@group_elem)
+ @group_elem.open(state)
+ end
+ group = nil
+ @members.each do |member|
+ group = member.adjust_group(state,group)
+ #puts "at:#{group.name}" if(group.respond_to?(:name))
+ state.endline()
+ state.needs_semi = true
+ state.pp(member)
+ state.endline()
+ end
+ group.adjust_to(state,nil) if(group)
+ if(@group_elem)
+ @group_elem.close(state)
+ end
+ end
+end
+class SWIGPre_Mask
+ def initialize(elem)
+ @elem = elem
+ end
+ def plan_cc(plan)
+ end
+ def plan_pre_swig(plan)
+ elem = MemberElementPreSWIG.new(@elem)
+ plan.push(elem)
+ end
+ def plan_post_swig(plan)
+ end
+ def plan_header(plan);
+ end
+end
+class SWIGPost_Mask
+ def initialize(elem)
+ @elem = elem
+ end
+ def plan_cc(plan)
+ end
+ def plan_pre_swig(plan)
+ end
+ def plan_post_swig(plan)
+ elem = MemberElementPostSWIG.new(@elem)
+ plan.push(elem)
+ end
+ def plan_header(plan);
+ end
+end
+class CC_Mask
+ def initialize(elem)
+ @elem = elem
+ end
+ def plan_cc(plan)
+ elem = MemberElementCC.new(@elem)
+ elem.pp_override = true
+ plan.push(elem)
+ end
+ def plan_header(plan);
+ end
+ def plan_pre_swig(plan);
+ end
+ def plan_post_swig(plan);
+ end
+end
+module Types
+ class TypeDef
+ def initialize(type,name)
+ @type = type
+ @name = name
+ end
+ def pp(state)
+ state.pp("typedef #{@type.name} #{@name}")
+ end
+ end
+ class Type
+ attr_accessor :name,:static,:dec,:space
+ def initialize(namespace,name)
+ @space = namespace
+ @name = name
+ @members = []
+ @protections = {}
+ @deps = []
+ end
+ class ProtectionGroup
+ def initialize(name)
+ @name = name
+ end
+ def adjust_from(state,other)
+ state.indent -= 1
+ state.pp("#@name:")
+ state.endline
+ state.indent += 1
+ end
+ def adjust_to(state,other)
+ other.adjust_from(state,self) if other
+ end
+ end
+ ProtectionGroups = { :public => ProtectionGroup.new(:public),
+ :protected => ProtectionGroup.new(:protected),
+ :private => ProtectionGroup.new(:private)}
+ def set_parent(parent)
+ @parent = parent
+ end
+ def chop_method_prefix()
+ @space.chop_method_prefix + "#@name::"
+ end
+ def def_func(*args)
+ func = CPP::MemberFunc.new(self,*args)
+ @protections[func] = @protection
+ @members << func
+ return func
+ end
+ def add_cc_comment(*args)
+ args.each do |arg|
+ @members.push(CC_Mask.new(CPP::Comment.new(arg)))
+ end
+ end
+ def add_pre_swig(arg)
+ @members.push(SWIGPre_Mask.new(arg))
+ end
+ def add_post_swig(arg)
+ @members.push(SWIGPost_Mask.new(arg))
+ end
+ def plan_pre_swig(plan)
+ @members.each do |member|
+ if(member.respond_to?(:plan_pre_swig))
+ member.plan_pre_swig(plan)
+ elsif(member.respond_to?(:pp_pre_swig_file))
+ plan.push(MemberElementPreSWIG.new(member))
+ end
+ end
+ end
+ def plan_post_swig(plan)
+ @members.each do |member|
+ if(member.respond_to?(:plan_post_swig))
+ member.plan_post_swig(plan)
+ elsif(member.respond_to?(:pp_post_swig_file))
+ plan.push(MemberElementPostSWIG.new(member))
+ end
+ end
+ end
+ def plan_cc(plan)
+ @members.each do |member|
+ if(member.respond_to?(:plan_cc))
+ member.plan_cc(plan)
+ elsif(member.respond_to?(:pp_cc_file))
+ plan.push(MemberElementCC.new(member))
+ end
+ end
+ end
+ def plan_header(plan)
+ group_plan = GroupPlan.new(self)
+ plan.push(group_plan)
+ @members.each do |member|
+ group_plan.implicit = ProtectionGroups[@protections[member]]
+ if(member.respond_to?(:plan_header))
+ member.plan_header(group_plan)
+ else
+ group_plan.push(MemberElementHeader.new(member))
+ end
+ #member.plan_cc(plan)
+ end
+ end
+ def open(state)
+ state.needs_semi = false
+ state.v_pad(2)
+ if(@static)
+ state.print("static ")
+ end
+ self.template_header(state) if(self.respond_to?(:template_header))
+ state.print("#{self.class.type_name} #{@name}")
+ self.template_spec_args(state) if(self.respond_to?(:template_spec_args))
+ if(@parent)
+ state.print(" : #{@parent} {\n")
+ else
+ state.pp(" {\n")
+ end
+ state.indent += 2
+ end
+ def close(state)
+ state.indent -= 2
+ state.needs_semi = true
+ if(@dec)
+ state.print("\n} #{@dec}")
+ else
+ state.print("\n}")
+ end
+ state.v_pad(2)
+ end
+ def add_dep(other)
+ @deps << other
+ self
+ end
+ end
+ class Class < Type
+ def add_member(protection,member)
+ @protection = protection
+ @members.push(member)
+ @protections[member] = protection
+ return member
+ end
+ def add_struct(*args)
+ add_member(:public, Types::Struct.new(self,*args))
+ end
+ def public() ; @protection = :public ; end
+ def protected() ; @protection = :protected ; end
+ def private() ; @protection = :private ; end
+ def self.type_name() ; "class" ; end
+ end
+ class PreprocessorIf < Type
+ def initialize(*args)
+ super(*args)
+ end
+ def add_member(member)
+ @members.push(member)
+ return member
+ end
+ def self.type_name() ; "#if" ; end
+ def open(state)
+ state.needs_semi = false
+ state.print("\n#if #{@name}")
+ end
+ def close(state)
+ state.needs_semi = false
+ state.print("\n#endif // #{@name}")
+ end
+ end
+ class Struct < Type
+ def add_member(member)
+ @members.push(member)
+ return member
+ end
+ def self.type_name() ; "struct" ; end
+ end
+ class TemplateClass < Class
+ def initialize(*args)
+ super(*args)
+ @t_args = CPP::Args.new()
+ end
+ def spec_args()
+ return @spec_args ||= CPP::Args.new()
+ end
+ def template_header(state)
+ if(@t_args.length > 0)
+ state.pp("template < ")
+ state.pp(@t_args)
+ else
+ state.pp("template <")
+ end
+ state.pp(">\n")
+ end
+ def plan_cc(plan)
+
+ end
+ def plan_header(plan)
+ group_plan = GroupPlan.new(self)
+ plan.push(group_plan)
+ @members.each do |member|
+ group_plan.implicit = ProtectionGroups[@protections[member]]
+ if(member.respond_to?(:plan_header))
+ member.plan_header(group_plan)
+ else
+ group_plan.push(MemberElementInline.new(member))
+ end
+ end
+ end
+ def template_spec_args(state)
+ if(@spec_args)
+ state.pp("< ")
+ state.pp(@spec_args)
+ state.pp(">")
+ end
+ end
+ end
+end
+class DepFilePair
+ class NameSpace
+ def initialize(name,parent)
+ @name,@parent = name,parent
+ @members = []
+ end
+ def add_struct(*args)
+ add Types::Struct.new(self,*args)
+ end
+ def add_template(*args)
+ add Types::TemplateClass.new(self,*args)
+ end
+ def add_class(*args)
+ add Types::Class.new(self,*args)
+ end
+ def add_cc(arg)
+ @members.push(CC_Mask.new(arg))
+ end
+ def add_pre_swig(arg)
+ @members.push(SWIGPre_Mask.new(arg))
+ end
+ def add_post_swig(arg)
+ @members.push(SWIGPost_Mask.new(arg))
+ end
+ def chop_method_prefix()
+ ""
+ end
+ def class_comment(*args)
+ add CPP::Comment.new(*args)
+ end
+ def var_dec_comment(*args)
+ add CPP::Comment.new(*args)
+ end
+ def add_var_dec(arg)
+ add DepMask.new(arg)
+ end
+ def plan_pre_swig(plan)
+ plan.implicit = ImplicitName.new(@name,plan.implicit)
+ @members.each do |member|
+ if(member.respond_to?(:plan_pre_swig))
+ member.plan_pre_swig(plan)
+ else
+ MemberElementPreSWIG.check(plan,member)
+ end
+ end
+ end
+ def plan_post_swig(plan)
+ @members.each do |member|
+ if(member.respond_to?(:plan_post_swig))
+ member.plan_post_swig(plan)
+ else
+ MemberElementPostSWIG.check(plan,member)
+ end
+ end
+ end
+ def plan_cc(plan)
+ plan.implicit = ImplicitName.new(@name,plan.implicit)
+ @members.each do |member|
+ if(member.respond_to?(:plan_cc))
+ member.plan_cc(plan)
+ else
+ MemberElementCC.check(plan,member)
+ end
+ end
+ plan.implicit = plan.implicit.parent
+ end
+ def plan_header(plan)
+ plan.implicit = ImplicitName.new(@name,plan.implicit)
+ @members.each do |member|
+ if(member.respond_to?(:plan_header))
+ member.plan_header(plan)
+ else
+ MemberElementHeader.check(plan,member)
+ end
+ end
+ plan.implicit = plan.implicit.parent
+ end
+ def add val
+ @members << val
+ val
+ end
+ end
+ def initialize(rel_path)
+ @rel_path = rel_path
+ @cc_includes = []
+ @swig_includes_h = []
+ @swig_includes_swig = []
+ @header_includes = []
+ @spaces = []
+ @cc_usings = []
+ @cache = {}
+ end
+ def add_swig_body_include(inc_path)
+ @swig_includes_swig << CPP::SwigInclude.new(inc_path)
+ end
+ def add_swig_header_include(inc_path)
+ @swig_includes_h << CPP::Include.new(inc_path)
+ end
+ def add_swig_include(inc_path)
+ @swig_includes_h << CPP::Include.new(inc_path)
+ @swig_includes_swig << CPP::SwigInclude.new(inc_path)
+ end
+ def add_cc_include(inc_path)
+ @cc_includes << CPP::Include.new(inc_path)
+ end
+ def add_cc_using(using)
+ @cc_usings << CPP::Using.new(using)
+ end
+ def add_header_include(inc_path)
+ @header_includes << CPP::Include.new(inc_path)
+ end
+ def add_namespace(name,parent)
+ space = NameSpace.new(name,parent)
+ if(parent != self)
+ parent.add(space)
+ else
+ @spaces.push(space)
+ end
+ return space
+ end
+ def set(type,cached)
+ @cache[type] = cached
+ end
+ def get(type)
+ cached = @cache[type]
+ return cached if cached
+ cached = type.create(self)
+ cached_check = @cache[type]
+ return cached_check if cached_check
+ set(type,cached)
+ return cached
+ end
+ def write_cc_file(cpp_base,cc_file)
+ plan_cc = GroupPlan.new(nil,elems_cc = [])
+ @spaces.each do |space|
+ space.plan_cc(plan_cc)
+ end
+ suite = CPP::Suite.new(@cc_includes + @cc_usings + [plan_cc])
+ CPP.pretty_print(suite,cc_file)
+ end
+ def write_header_file(cpp_base,header_file)
+ plan_header = GroupPlan.new(nil,elems_cc = [])
+ @spaces.each do |space|
+ space.plan_header(plan_header)
+ end
+ suite = CPP::Suite.new(@header_includes + [plan_header])
+ include_guard = CPP::IncludeGuard.new(suite)
+ include_guard.name = @rel_path.upcase.gsub(/[\.\/\\]/,"_") + "_H_"
+ CPP.pretty_print(include_guard,header_file)
+ end
+ def write_swig_file(cpp_base,swig_file,q_filename)
+ plan_pre_swig = GroupPlan.new(nil, elems_cc = [])
+ plan_post_swig = GroupPlan.new(nil, elems_cc = [])
+ q_filename_underscore = q_filename.gsub(".","_")
+ @spaces.each do |space|
+ space.plan_pre_swig(plan_pre_swig)
+ space.plan_post_swig(plan_post_swig)
+ end
+ header_includes = CPP::SWIGBraces.new(CPP::Suite.new(@swig_includes_h))
+ # TODO(aschuh): I should probably %import any other headers from this queue's dependencies.
+ suite = CPP::Suite.new(["%module \"#{q_filename_underscore}\"",
+ "%typemap(javaimports) SWIGTYPE, SWIGTYPE * \"import aos.QueueGroup; import aos.Message; import aos.Time;\"",
+ "%pragma(java) jniclassimports=\"import aos.QueueGroup; import aos.Message; import aos.Time;\"",
+ "%pragma(java) moduleimports=\"import aos.QueueGroup; import aos.Message; import aos.Time;\"",
+ "%include \"std_string.i\"",
+ "%include \"stdint.i\""] +
+ [header_includes] +
+ #["%import \"aos/common/time.h\"",
+ #"%import \"aos/common/queue.h\""] +
+ ["%import \"aos/aos.swig\""] +
+ [plan_pre_swig] +
+ @swig_includes_swig +
+ [plan_post_swig]
+ )
+ CPP.pretty_print(suite, swig_file)
+ end
+end
diff --git a/aos/build/queues/cpp_pretty_print/file_pair_types.rb b/aos/build/queues/cpp_pretty_print/file_pair_types.rb
new file mode 100644
index 0000000..8f60b77
--- /dev/null
+++ b/aos/build/queues/cpp_pretty_print/file_pair_types.rb
@@ -0,0 +1,204 @@
+module CPP
+end
+class CPP::TypePair
+ attr_accessor :name,:static,:dec
+ def initialize(namespace,name)
+ @space,@name = namespace,name
+ @members = []
+ @protections = {}
+ @dont_sort = {}
+ end
+ ProtectionTable = { :public => 0,:protected => 1,:private => 2 }
+ def comp(m1,m2)
+ if(!(@dont_sort[m1] || @dont_sort[m2]))
+ if(@protections[m1] && @protections[m2])
+ comp = ProtectionTable[@protections[m1]] <=> ProtectionTable[@protections[m2]]
+ return comp if(comp != 0)
+ end
+ comp = TypeTable[m1.class] <=> TypeTable[m2.class]
+ return comp if(comp != 0)
+ end
+ return @stable[m1] <=> @stable[m2]
+ end
+ def set_parent(parent)
+ @parent = parent
+ end
+ def add_class(name)
+ return add_member(:public,CPP::ClassPair.new(self,name))
+ end
+ def add_struct(name)
+ return add_member(:public,CPP::StructPair.new(self,name))
+ end
+ def add_cc_comment(*strs)
+ strs.each do |str|
+ @members << comment = CPP::CCMemberWrapper.new(CPP::Comment.new(str))
+ @protections[comment] = @protection
+ end
+ #@dont_sort[comment] = true
+ end
+ def method_prefix()
+ @space.method_prefix + "#@name::"
+ end
+ def chop_method_prefix()
+ @space.chop_method_prefix + "#@name::"
+ end
+ def pp(state)
+ @stable = {}
+ @members.each_with_index { |mem,i| @stable[mem] = i }
+ members = @members.sort { |m1,m2| comp(m1,m2) }
+
+ state.needs_semi = false
+ state.v_pad(2)
+ if(@static)
+ state.print("static ")
+ end
+ if(@parent)
+ state.print("#{self.class.type_name} #{@name} : #{@parent} {\n")
+ else
+ state.print("#{self.class.type_name} #{@name} {\n")
+ end
+ state.indent += 2
+ protection = nil
+ members.each do |member|
+ if(protection != @protections[member])
+ state.indent -= 1
+ state.needs_semi = false
+ state.v_pad(2) if(protection)
+ protection = @protections[member]
+ state.print("#{protection}:\n")
+ state.indent += 1
+ state.endline()
+ end
+ state.endline()
+ state.needs_semi = true
+ if(member.respond_to?(:pp_header_file))
+ member.pp_header_file(state)
+ else
+ state.pp(member)
+ end
+ state.endline()
+ end
+ state.indent -= 2
+ state.needs_semi = true
+ if(@dec)
+ state.print("\n} #{@dec}")
+ else
+ state.print("\n}")
+ end
+ state.v_pad(2)
+ end
+ def pp_header_file(state)
+ pp(state)
+ end
+ def pp_cc_file(state)
+ @members.each do |member|
+ state.needs_semi = true
+ member.pp_cc_file(state) if(member.respond_to?(:pp_cc_file))
+ state.endline()
+ end
+ end
+ def def_func(*args)
+ func = CPP::MemberFunc.new(self,*args)
+ @protections[func] = @protection
+ @members << func
+ return func
+ end
+end
+class CPP::CCMemberWrapper
+ def initialize(member)
+ @member = member
+ end
+ def pp_header_file(state) ; end
+ def pp_cc_file(state)
+ state.pp(@member)
+ end
+end
+class CPP::ClassPair < CPP::TypePair
+ attr_accessor :name
+ def initialize(namespace,name)
+ super(namespace,name)
+ @protection = :public #default to public
+ end
+ def add_member(protection,member)
+ @protection = protection
+ @members << member
+ @protections[member] = protection
+ return member
+ end
+ def public() ; @protection = :public ; end
+ def protected() ; @protection = :protected ; end
+ def private() ; @protection = :private ; end
+ def self.type_name() ; "class" ; end
+end
+class CPP::StructPair < CPP::TypePair
+ def self.type_name() ; "struct" ; end
+ def add_member(member)
+ @members << member
+ return member
+ end
+end
+CPP::TypePair::TypeTable = { CPP::StructPair => 0, CPP::ClassPair => 1,CPP::Constructor => 2 }
+CPP::TypePair::TypeTable.default = 3
+class CPP::TemplateClass < CPP::ClassPair
+ def initialize(namespace,name)
+ super(namespace,name)
+ @t_args = CPP::Args.new()
+ end
+ def spec_args()
+ return @spec_args ||= CPP::Args.new()
+ end
+ def pp(state)
+ @stable = {}
+ @members.each_with_index { |mem,i| @stable[mem] = i }
+ members = @members.sort { |m1,m2| comp(m1,m2) }
+ state.needs_semi = false
+ state.v_pad(2)
+ if(@t_args.length > 0)
+ state.pp("template < ")
+ state.pp(@t_args)
+ else
+ state.pp("template <")
+ end
+ state.pp(">\n")
+ state.pp("class #@name")
+ if(@spec_args)
+ state.pp("< ")
+ state.pp(@spec_args)
+ state.pp("> {")
+ else
+ state.pp(" {")
+ end
+ state.endline()
+ state.indent += 2
+ protection = nil
+ members.each do |member|
+ if(protection != @protections[member])
+ state.indent -= 1
+ state.needs_semi = false
+ state.v_pad(2) if(protection)
+ protection = @protections[member]
+ state.print("#{protection}:\n")
+ state.indent += 1
+ state.endline()
+ end
+ state.endline()
+ state.needs_semi = true
+ if(member.respond_to?(:pp_inline))
+ member.pp_inline(state)
+ else
+ state.pp(member)
+ end
+ state.endline()
+ end
+ state.indent -= 2
+ state.needs_semi = true
+ if(@dec)
+ state.print("\n} #{@dec}")
+ else
+ state.print("\n}")
+ end
+ state.v_pad(2)
+ end
+ def pp_cc_file(state); end
+end
+
diff --git a/aos/build/queues/cpp_pretty_print/standard_types.rb b/aos/build/queues/cpp_pretty_print/standard_types.rb
new file mode 100644
index 0000000..566f542
--- /dev/null
+++ b/aos/build/queues/cpp_pretty_print/standard_types.rb
@@ -0,0 +1,363 @@
+module CPP
+ class Class
+
+ end
+ class Funct
+ attr_accessor :retval,:name,:args,:suite
+ def initialize(retval = nil,name = nil,args = Args.new(),suite = Suite.new())
+ @retval,@name,@args,@suite = retval,name,args,suite
+ end
+ def pp(state)
+ state.pp(@retval)
+ state.print(" ")
+ state.pp(@name)
+ state.print("(")
+ state.pp(@args)
+ state.print(")")
+ state.pp(@suite)
+ end
+ end
+ class If
+ attr_accessor :cond,:suite,:else_suite
+ def initialize(cond = nil,suite = Suite.new(),else_suite = nil)
+ @cond,@suite,@else_suite = cond,suite,else_suite
+ end
+ def pp(state)
+ state.print("if (")
+ state.pp(@cond)
+ state.print(") ")
+ state.needs_semi = false
+ state.pp(@suite)
+ if(@else_suite)
+ state.print(" else ")
+ state.pp(@else_suite)
+ end
+ end
+ def else_suite()
+ return(@else_suite ||= Suite.new())
+ end
+ end
+ class For
+ attr_accessor :init,:cond,:update,:suite
+ def initialize(init = nil,cond = nil,update = nil,suite = Suite.new())
+ @init,@cond,@update,@suite = init,cond,update,suite
+ end
+ def pp(state)
+ state.print("for (")
+ Args.new([@init,@cond,@update]).pp(state,";")
+ state.print(") ")
+ state.needs_semi = false
+ state.pp(@suite)
+ end
+ end
+ class Args < Array
+ attr_accessor :dont_wrap
+ def pp(state,sep = ",")
+ pos = start = state.col
+ self.each_with_index do |arg,i|
+ #puts "#{state.col - start} , #{start}"
+ state.print(sep) if(i != 0)
+ if(pos > 80)
+ state.wrap(state.indent + 4)
+ pos = start = state.col
+ elsif(state.col * 2 - pos > 80 && !@dont_wrap)
+ state.wrap(start)
+ start = pos
+ else
+ state.print(" ") if(i != 0)
+ pos = state.col
+ end
+ state.pp(arg)
+ end
+ end
+ end
+ class Suite < Array
+ def pp(state)
+ state.print("{")
+ state.>>
+ state.needs_semi = false
+ self.pp_no_braces(state)
+ state.<<
+ state.print("}")
+ end
+ def pp_no_braces(state)
+ self.each do |arg,i|
+ state.endline()
+ state.needs_semi = true
+ state.pp(arg)
+ state.endline()
+ end
+ end
+ def pp_one_line(state)
+ if(self.length == 1)
+ state.needs_semi = true
+ state.print("{ ")
+ state.pp(self[0])
+ state.print(";") if(state.needs_semi)
+ state.needs_semi = false
+ state.print(" }")
+ else
+ self.pp(state)
+ end
+ end
+ end
+ class FuncCall
+ attr_accessor :name,:args
+ def initialize(name = nil,args = Args.new())
+ @name,@args = name,args
+ end
+ def self.build(name,*args)
+ self.new(name,Args.new(args))
+ end
+ def pp(state)
+ state.pp(@name)
+ state.print("(")
+ state.pp(@args)
+ state.print(")")
+ end
+ end
+ class BIT_OR
+ attr_accessor :val1,:val2
+ def initialize(val1,val2)
+ @val1,@val2 = val1,val2
+ end
+ def pp(state)
+ state.pp(@val1)
+ state.print(" | ")
+ state.pp(@val2)
+ end
+ end
+ class LT
+ attr_accessor :val1,:val2
+ def initialize(val1,val2)
+ @val1,@val2 = val1,val2
+ end
+ def pp(state)
+ state.pp(@val1)
+ state.print(" < ")
+ state.pp(@val2)
+ end
+ end
+ class Div
+ attr_accessor :val1,:val2
+ def initialize(val1,val2)
+ @val1,@val2 = val1,val2
+ end
+ def pp(state)
+ state.pp(@val1)
+ state.print(" / ")
+ state.pp(@val2)
+ end
+ end
+ class Add
+ attr_accessor :val1,:val2
+ def initialize(val1,val2)
+ @val1,@val2 = val1,val2
+ end
+ def pp(state)
+ state.pp(@val1)
+ state.print(" + ")
+ state.pp(@val2)
+ end
+ end
+ class Member
+ attr_accessor :obj,:name
+ def initialize(obj,name)
+ @obj,@name = obj,name
+ end
+ def pp(state)
+ state.pp(@obj)
+ state.print(".")
+ state.pp(@name)
+ end
+ end
+ class PointerMember
+ attr_accessor :obj,:name
+ def initialize(obj,name)
+ @obj,@name = obj,name
+ end
+ def pp(state)
+ state.pp(@obj)
+ state.print("->")
+ state.pp(@name)
+ end
+ end
+ class Minus
+ attr_accessor :val
+ def initialize(val)
+ @val = val
+ end
+ def pp(state)
+ state.print("-")
+ state.pp(@val)
+ end
+ end
+ class Not
+ attr_accessor :val
+ def initialize(val)
+ @val = val
+ end
+ def pp(state)
+ state.print("!")
+ state.pp(@val)
+ end
+ end
+ class Address
+ attr_accessor :val
+ def initialize(val)
+ @val = val
+ end
+ def pp(state)
+ state.print("&")
+ state.pp(@val)
+ end
+ end
+ class Paran
+ attr_accessor :val
+ def initialize(val)
+ @val = val
+ end
+ def pp(state)
+ state.print("(")
+ state.pp(@val)
+ state.print(")")
+ end
+ end
+ class Assign
+ attr_accessor :lval,:rval
+ def initialize(lval = nil,rval = Args.new())
+ @lval,@rval = lval,rval
+ end
+ def pp(state)
+ state.pp(@lval)
+ state.print(" = ")
+ state.pp(@rval)
+ end
+ end
+ class PointerDeref
+ attr_accessor :val
+ def initialize(val)
+ @val = val
+ end
+ def pp(state)
+ state.print("*")
+ state.pp(@val)
+ end
+ end
+ class Cast
+ attr_accessor :to,:val
+ def initialize(to,val)
+ @to,@val = to,val
+ end
+ def pp(state)
+ state.print("(")
+ state.pp(@to)
+ state.print(")")
+ state.pp(@val)
+ end
+ end
+ class VarDec
+ attr_accessor :type,:name
+ def initialize(type = nil,name = nil)
+ @type,@name = type,name
+ end
+ def pp(state)
+ state.pp(@type)
+ state.print(" ")
+ state.pp(@name)
+ end
+ end
+ class Return
+ attr_accessor :val
+ def initialize(val = nil)
+ @val = val
+ end
+ def pp(state)
+ state.print("return ")
+ state.pp(@val)
+ end
+ end
+ class TraversalState
+ attr_accessor :needs_semi,:indent,:col
+ def initialize(file)
+ @file = file
+ @indent = 0
+ @not_indented = true
+ @just_endlined = true
+ @hold_points = []
+ @col = 0
+ end
+ def set_hold_point()
+ @hold_points.push(@col)
+ end
+ def wrap(col)
+ @file.print("\n")
+ @file.print(" " * col)
+ @col = col
+ end
+ def suppress_indent()
+ @not_indented = false
+ end
+ def <<()
+ @indent -= 2
+ end
+ def >>()
+ @indent += 2
+ end
+ def pp(ast)
+ return ast.pp(self) if(ast.respond_to?(:pp))
+ self.print(ast)
+ end
+ def print(chars)
+ return print_no_split(chars) if(!chars.respond_to?(:split))
+ chars.split(/\n/,-1).each_with_index do |line,i|
+ endline() if(i != 0)
+ print_no_split(line) if(line && line.length > 0)
+ end
+ end
+ def print_no_split(chars)
+ if(@not_indented)
+ @file.print(" "*@indent)
+ @col += @indent
+ @not_indented = false
+ end
+ if(chars)
+ chars = chars.to_s
+ if(chars.length > 0)
+ @col += chars.length
+ @file.print(chars)
+ @just_endlined = false
+ @v_pad = 0
+ end
+ end
+ end
+ def endline()
+ return if(@just_endlined)
+ @file.print(";") if(@needs_semi)
+ @needs_semi = false
+ @file.print("\n")
+ @not_indented = true
+ @just_endlined = true
+ @hold_points.clear()
+ @v_pad += 1
+ @col = 0
+ end
+ def v_pad(n)
+ while(@v_pad < n)
+ force_endline()
+ end
+ end
+ def force_endline()
+ @just_endlined = false
+ endline()
+ end
+ end
+ def self.pretty_print(ast,file)
+ state = TraversalState.new(file)
+ if(ast.respond_to?(:pp_no_braces))
+ ast.pp_no_braces(state)
+ else
+ state.pp(ast)
+ end
+ end
+end
diff --git a/aos/build/queues/cpp_pretty_print/swig.rb b/aos/build/queues/cpp_pretty_print/swig.rb
new file mode 100644
index 0000000..ac6d062
--- /dev/null
+++ b/aos/build/queues/cpp_pretty_print/swig.rb
@@ -0,0 +1,60 @@
+class CPP::SwigPragma
+ attr_accessor :suite
+ def initialize(language, pragmatype, suite = CPP::Suite.new())
+ @suite = suite
+ @language = language
+ @pragmatype = pragmatype
+ end
+ def pp(state)
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("%pragma(#{@language}) #{@pragmatype}=%{")
+ state.endline()
+ if(@suite.respond_to?(:pp_no_braces))
+ @suite.pp_no_braces(state)
+ else
+ state.pp(@suite)
+ end
+ state.endline()
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("%}")
+ state.endline()
+ state.endline()
+ end
+end
+class CPP::SWIGBraces
+ attr_accessor :suite
+ def initialize(suite = CPP::Suite.new())
+ @suite = suite
+ end
+ def pp(state)
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("%{")
+ state.endline()
+ if(@suite.respond_to?(:pp_no_braces))
+ @suite.pp_no_braces(state)
+ else
+ state.pp(@suite)
+ end
+ state.endline()
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("%}")
+ state.endline()
+ state.endline()
+ end
+end
+class CPP::SwigInclude
+ attr_accessor :filename
+ def initialize(filename)
+ @filename = filename
+ end
+ def pp(state)
+ state.needs_semi = false
+ state.suppress_indent()
+ state.print("%include #{@filename}")
+ state.endline()
+ end
+end
diff --git a/aos/build/queues/objects/errors.rb b/aos/build/queues/objects/errors.rb
new file mode 100644
index 0000000..d776a22
--- /dev/null
+++ b/aos/build/queues/objects/errors.rb
@@ -0,0 +1,43 @@
+class QError < Exception
+ def initialize(msg)
+ super()
+ @msg = msg
+ @qstacktrace = []
+ end
+ def self.set_name(name)
+ @pretty_name = name
+ end
+ def self.pretty_name()
+ @pretty_name
+ end
+ def to_s
+ msg = "Error:(#{self.class.pretty_name})\n\t"
+ msg += @msg
+ msg += "\n" if(msg[-1] != "\n")
+ @qstacktrace.each do |part|
+ part = part.q_stack_name if(part.respond_to?(:q_stack_name))
+ msg += "\tfrom: #{part}\n"
+ end
+ return msg
+ end
+ set_name("Base Level Exception.")
+ attr_accessor :qstacktrace
+end
+class QSyntaxError < QError
+ def initialize(msg)
+ super(msg)
+ end
+ set_name("Syntax Error")
+end
+class QNamespaceCollision < QError
+ def initialize(msg)
+ super(msg)
+ end
+ set_name("Namespace Collision")
+end
+class QImportNotFoundError < QError
+ def initialize(msg)
+ super(msg)
+ end
+ set_name("Couldn't Find Target of Import Statement")
+end
diff --git a/aos/build/queues/objects/interface.rb b/aos/build/queues/objects/interface.rb
new file mode 100644
index 0000000..52332b6
--- /dev/null
+++ b/aos/build/queues/objects/interface.rb
@@ -0,0 +1,69 @@
+class MessageElementReq
+ def initialize(type,name)
+ @type = type
+ @name = name
+ end
+ def self.parse(tokens)
+ type = tokens.expect(:tWord).data
+ name = tokens.expect(:tWord).data
+ tokens.expect(:tSemi)
+ return self.new(type,name)
+ end
+end
+class QueueReq
+ def initialize(name,type = nil)
+ @name = name
+ @type = type
+ end
+ def self.parse(tokens)
+ type_or_name = tokens.expect(:tWord).data
+ if(tokens.peak == :tSemi)
+ tokens.expect(:tSemi)
+ return self.new(type_or_name)
+ else
+ name = tokens.expect(:tWord).data
+ tokens.expect(:tSemi)
+ return self.new(name,type_or_name)
+ end
+ end
+end
+class InterfaceStmt < QStmt
+ def initialize(name,elements)
+ @name = name
+ @elements = elements
+ end
+ def q_eval(locals)
+
+ end
+ def self.check_type(tokens,new_type,old_type)
+ return new_type if(old_type == nil)
+ if(new_type != old_type)
+ tokens.qError(<<ERROR_MSG)
+error: intermixing queue definitions (a queue_group feature)
+ and type definitions (a message_group feature)
+ this results in an undefined type value.
+ Wot. Wot.
+ERROR_MSG
+ end
+ return old_type
+ end
+ def self.parse(tokens)
+ name = tokens.expect(:tWord).data
+ values = []
+ type = nil
+ tokens.expect(:tOpenB)
+ while(tokens.peak != :tCloseB)
+ if(tokens.peak.data == "queue")
+ tokens.expect(:tWord)
+ values << QueueReq.parse(tokens)
+ type = check_type(tokens,:queue_group,type)
+ else
+ values << MessageElementReq.parse(tokens)
+ type = check_type(tokens,:message_group,type)
+ end
+ end
+ tokens.expect(:tCloseB)
+ tokens.expect(:tSemi)
+ self.new(name,values)
+ end
+end
diff --git a/aos/build/queues/objects/namespaces.rb b/aos/build/queues/objects/namespaces.rb
new file mode 100644
index 0000000..b799d36
--- /dev/null
+++ b/aos/build/queues/objects/namespaces.rb
@@ -0,0 +1,210 @@
+class LocalSituation
+ attr_accessor :globals,:local
+ def initialize(globals)
+ @globals = globals
+ @local = nil
+ end
+ def package=(qualified)
+ if(@local)
+ raise QSyntaxError.new(<<ERROR_MSG)
+You are redefining the package path.
+ Stuff might break if you do that.
+ Other options include: using another header file, and just using the same namespace.
+ If you are confident that you need this you can remove this check at
+ #{__FILE__}:#{__LINE__}.
+ Or file a feature request.
+ But that would be weird...
+ Wot. Wot.
+ERROR_MSG
+ end
+ @local = @globals.space
+ qualified.names.each do |name|
+ @local = @local.get_make(name)
+ end
+ end
+ def register(value)
+ if(!@local)
+ raise QError.new(<<ERROR_MSG)
+There is no package path defined, This is a big problem because
+ we are kindof expecting you to have a package path...
+ use a :
+ package my_super.cool.project;
+ statement to remedy this situation. (or file a feature request)
+ Wot. Wot.
+ERROR_MSG
+ end
+ @local[value.name] = value
+ value.parent = @local if(value.respond_to?(:parent=))
+ value.loc = @local
+ end
+ def bind(bind_to)
+ return BoundSituation.new(self,bind_to)
+ end
+end
+class BoundSituation < LocalSituation
+ def initialize(locals,bind_to)
+ @globals = globals
+ @local = bind_to
+ end
+end
+class NameSpace
+ attr_accessor :parent,:name
+ def initialize(name = nil,parent = nil)
+ @name = name
+ @parent = parent
+ @spaces = {}
+ end
+ def []=(key,val)
+ if(old_val = @spaces[key])
+ old_val = old_val.created_by if(old_val.respond_to?(:created_by) && old_val.created_by)
+ if(old_val.respond_to?(:q_stack_name))
+ old_val = old_val.q_stack_name
+ else
+ old_val = "eh, it is a #{old_val.class} thats all I know..."
+ end
+ raise QNamespaceCollision.new(<<ERROR_MSG)
+Woah! The name #{queue_name(key).inspect} is already taken by some chap at #{old_val}.
+\tFind somewhere else to peddle your wares.
+\tWot. Wot.
+ERROR_MSG
+ end
+ @spaces[key] = val
+ end
+ def to_cpp_id(name)
+ txt = @name + "::" + name
+ return @parent.to_cpp_id(txt) if(@parent && parent.name)
+ return "::" + txt
+ end
+ def queue_name(queue)
+ get_name() + "." + queue
+ end
+ def [](key)
+ #puts "getting #{get_name}.#{key}"
+ @spaces[key]
+ end
+ def get_make(name)
+ @spaces[name] ||= self.class.new(name,self)
+ end
+ def get_name()
+ if(@parent)
+ return "#{@parent.get_name}.#{@name}"
+ else
+ return "#{@name}"
+ end
+ end
+ def create(cpp_tree)
+ if(@parent && @parent.name)
+ parent = cpp_tree.get(@parent)
+ else
+ parent = cpp_tree
+ end
+ return cpp_tree.add_namespace(@name,parent)
+ end
+ def to_s()
+ "<NameSpace: #{get_name()}>"
+ end
+ def inspect()
+ "<NameSpace: #{get_name()}>"
+ end
+ def root()
+ return self if(@parent == nil)
+ return @parent.root
+ end
+end
+class Globals
+ attr_accessor :space
+ def initialize()
+ @space = NameSpace.new()
+ @space.get_make("aos")
+ @include_paths = []
+ end
+ def paths()
+ @include_paths
+ end
+ def add_path(path)
+ @include_paths << path
+ end
+ def find_file(filename)
+ @include_paths.each do |path_name|
+ new_path = File.expand_path(path_name) + "/" + filename
+ if(File.exists?(new_path))
+ return new_path
+ end
+ end
+ raise QImportNotFoundError.new(<<ERROR_MSG)
+Problem Loading:#{filename.inspect} I looked in:
+\t#{(@include_paths.collect {|name| name.inspect}).join("\n\t")}
+\tbut alas, it was nowhere to be found.
+\tIt is popular to include the top of the repository as the include path start,
+\tand then reference off of that.
+\tI would suggest doing that and then trying to build again.
+\tWot. Wot.
+ERROR_MSG
+ end
+end
+class QualifiedName
+ attr_accessor :names,:off_root
+ def initialize(names,off_root = false)
+ @names = names
+ @off_root = off_root
+ end
+ def test_lookup(namespace)
+ @names.each do |name|
+ namespace = namespace[name]
+ return nil if(!namespace)
+ end
+ return namespace
+ end
+ def is_simple?()
+ return !@off_root && @names.length == 1
+ end
+ def to_simple()
+ return @names[-1]
+ end
+ def to_s()
+ if(@off_root)
+ return ".#{@names.join(".")}"
+ else
+ return @names.join(".")
+ end
+ end
+ def lookup(locals)
+ if(@off_root)
+ local = locals.globals.space
+ else
+ local = locals.local
+ end
+ target = nil
+ while(!target && local)
+ target = test_lookup(local)
+ local = local.parent
+ end
+ return target if(target)
+ if(@off_root)
+ raise QError.new(<<ERROR_MSG)
+I was looking for .#{@names.join(".")}, but alas, it was not under
+\tthe root namespace.
+\tI'm really sorry old chap.
+\tWot. Wot.
+ERROR_MSG
+ else
+ raise QError.new(<<ERROR_MSG)
+I was looking for #{@names.join(".")}, but alas, I could not find
+\tit in #{locals.local.get_name} or any parent namespaces.
+\tI'm really sorry old chap.
+\tWot. Wot.
+ERROR_MSG
+ end
+ end
+ def self.parse(tokens)
+ names = []
+ off_root = (tokens.peak == :tDot)
+ tokens.next if(off_root)
+ names << tokens.expect(:tWord).data
+ while(tokens.peak == :tDot)
+ tokens.next
+ names << tokens.expect(:tWord).data
+ end
+ return self.new(names,off_root)
+ end
+end
diff --git a/aos/build/queues/objects/q_file.rb b/aos/build/queues/objects/q_file.rb
new file mode 100644
index 0000000..f683dda
--- /dev/null
+++ b/aos/build/queues/objects/q_file.rb
@@ -0,0 +1,148 @@
+class QStmt
+ def set_line(val)
+ @file_line = val
+ return self
+ end
+ def q_stack_name()
+ @file_line
+ end
+ def self.method_added(name)
+ @wrapped ||= {}
+ return if(name != :q_eval && name != :q_eval_extern)
+ return if(@wrapped[name])
+ @wrapped[name] = true
+ method = self.instance_method(name)
+ define_method(name) do |*args,&blk|
+ begin
+ method.bind(self).call(*args,&blk)
+ rescue QError => e
+ e.qstacktrace << self
+ raise e
+ end
+ end
+ end
+
+end
+class ImportStmt < QStmt
+ def initialize(filename)
+ @filename = filename
+ end
+ def q_eval(locals)
+ filename = locals.globals.find_file(@filename)
+ #puts "importing #{filename.inspect}"
+ q_file = QFile.parse(filename)
+ q_output = q_file.q_eval_extern(locals.globals)
+ q_output.extern = true
+ return Target::QInclude.new(@filename + ".h")
+ end
+ def self.parse(tokens)
+ line = tokens.pos
+ to_import = (tokens.expect(:tString) do |token|
+ <<ERROR_MSG
+I found a #{token.humanize} at #{token.pos}.
+\tI was really looking for a "filename" for this import statement.
+\tSomething like: import "super_cool_file";
+\tWot.Wot
+ERROR_MSG
+ end).data
+ tokens.expect(:tSemi) do |token|
+ <<ERROR_MSG
+I found a #{token.humanize} at #{token.pos}.
+\tI was really looking for a ";" to finish off this import statement
+\tat line #{line};
+\tSomething like: import #{to_import.inspect};
+\tWot.Wot #{" "*to_import.inspect.length}^
+ERROR_MSG
+ end
+ return self.new(to_import).set_line(line)
+ end
+end
+class PackageStmt < QStmt
+ def initialize(name)
+ @name = name
+ end
+ def q_eval(locals)
+ locals.package = @name
+ return nil
+ end
+ def self.parse(tokens)
+ line = tokens.pos
+ qualified_name = QualifiedName.parse(tokens)
+ tokens.expect(:tSemi)
+ return self.new(qualified_name).set_line(line)
+ end
+end
+class QFile
+ attr_accessor :namespace
+ def initialize(filename,suite)
+ @filename,@suite = filename,suite
+ end
+ def q_eval(globals = Globals.new())
+ local_pos = LocalSituation.new(globals)
+ q_file = Target::QFile.new()
+ @suite.each do |name|
+ val = name.q_eval(local_pos)
+ if(val)
+ if(val.respond_to?(:create))
+ q_file.add_type(val)
+ end
+ end
+ end
+ @namespace = local_pos.local
+ return q_file
+ end
+ def q_eval_extern(globals)
+ local_pos = LocalSituation.new(globals)
+ q_file = Target::QFile.new()
+ @suite.each do |name|
+ if(name.respond_to?(:q_eval_extern))
+ val = name.q_eval_extern(local_pos)
+ else
+ val = name.q_eval(local_pos)
+ end
+ if(val)
+ if(val.respond_to?(:create))
+ q_file.add_type(val)
+ end
+ end
+ end
+ return q_file
+ end
+ def self.parse(filename)
+ tokens = Tokenizer.new(filename)
+ suite = []
+ while(tokens.peak != :tEnd)
+ token = tokens.expect(:tWord) do |token| #symbol
+ <<ERROR_MSG
+I found a #{token.humanize} at #{token.pos}.
+\tI was really looking for a "package", "import", "queue_group",
+\t"message", or "queue" statement to get things moving.
+\tSomething like: import "super_cool_file";
+\tWot.Wot
+ERROR_MSG
+ end
+ case token.data
+ when "package"
+ suite << PackageStmt.parse(tokens)
+ when "import"
+ suite << ImportStmt.parse(tokens)
+ when "queue_group"
+ suite << QueueGroupStmt.parse(tokens)
+ when "message"
+ suite << MessageStmt.parse(tokens)
+ when "queue"
+ suite << QueueStmt.parse(tokens)
+ when "interface"
+ suite << InterfaceStmt.parse(tokens)
+ else
+ tokens.qError(<<ERROR_MSG)
+expected a "package","import","queue","queue_group", or "message" statement rather
+ than a #{token.data.inspect}, (whatever that is?)
+ oh! no! a feature request!?
+ Wot. Wot.
+ERROR_MSG
+ end
+ end
+ return self.new(filename,suite)
+ end
+end
diff --git a/aos/build/queues/objects/queue.rb b/aos/build/queues/objects/queue.rb
new file mode 100644
index 0000000..5693486
--- /dev/null
+++ b/aos/build/queues/objects/queue.rb
@@ -0,0 +1,154 @@
+class MessageElementStmt < QStmt
+ attr_accessor :name
+ def initialize(type,name,length = nil) #lengths are for arrays
+ @type = type
+ @name = name
+ @length = length
+ end
+ CommonMistakes = {"short" => "int16_t","int" => "int32_t","long" => "int64_t"}
+ def check_type_error()
+ if(!(Sizes[@type] || (@length != nil && @type == "char")) )
+ if(correction = CommonMistakes[@type])
+ raise QError.new(<<ERROR_MSG)
+Hey! you have a \"#{@type}\" in your message statement.
+\tplease use #{correction} instead. Your type is not supported because we
+\twant to guarantee that the sizes of the messages stay the same across platforms.
+\tWot. Wot.
+ERROR_MSG
+ elsif(@type == "char")
+ raise QError.new(<<ERROR_MSG)
+Hey! you have a \"#{@type}\" in your message statement.
+\tyou need your declaration to be a char array like: char[10].
+\tor, please use int8_t or uint8_t.
+\tWot. Wot.
+ERROR_MSG
+ else
+ raise QError.new(<<ERROR_MSG)
+Hey! you have a \"#{@type}\" in your message statement.
+\tThat is not in the list of supported types.
+\there is the list of supported types:
+\tint{8,16,32,64}_t,uint{8,16,32,64}_t,bool,float,double#{len_comment}
+\tWot. Wot.
+ERROR_MSG
+ end
+ end
+ end
+
+ PrintFormat = {"bool" => "%c",
+ "float" => "%f",
+ "char" => "%c",
+ "double" => "%f",
+ "uint8_t" => "%\"PRIu8\"",
+ "uint16_t" => "%\"PRIu16\"",
+ "uint32_t" => "%\"PRIu32\"",
+ "uint64_t" => "%\"PRIu64\"",
+ "int8_t" => "%\"PRId8\"",
+ "int16_t" => "%\"PRId16\"",
+ "int32_t" => "%\"PRId32\"",
+ "int64_t" => "%\"PRId64\""}
+ def toPrintFormat()
+ if(format = PrintFormat[@type])
+ return format;
+ end
+ raise QError.new(<<ERROR_MSG)
+Somehow this slipped past me, but
+\tI couldn't find the print format of #{@type}. Really, my bad.
+\tWot. Wot.
+ERROR_MSG
+ end
+
+ Sizes = {"bool" => 1, "float" => 4,"double" => 8}
+ [8,16,32,64].each do |len|
+ Sizes["int#{len}_t"] = len / 8
+ Sizes["uint#{len}_t"] = len / 8
+ end
+ Zero = {"float" => "0.0f","double" => "0.0","bool" => "false"}
+ def size()
+ if(size = Sizes[@type]); return size; end
+ return 1 if(@type == "char")
+ raise QError.new(<<ERROR_MSG)
+Somehow this slipped past me, but
+\tI couldn't find the size of #{@type}. Really, my bad.
+\tWot. Wot.
+ERROR_MSG
+ end
+ def q_eval(locals)
+ check_type_error()
+ if(@length == nil)
+ member = Target::MessageElement.new(@type,@name)
+ else
+ member = Target::MessageArrayElement.new(@type,@name,@length)
+ end
+ member.size = size()
+ member.zero = Zero[@type] || "0";
+ member.printformat = toPrintFormat()
+ locals.local.add_member(member)
+ end
+ def self.parse(tokens)
+ line = tokens.pos
+ type = tokens.expect(:tWord).data
+ len = nil
+ if(tokens.peak == :tOpenB)
+ tokens.expect(:tOpenB)
+ len = tokens.expect(:tNumber).data
+ tokens.expect(:tCloseB)
+ end
+ name = tokens.expect(:tWord).data
+ tokens.expect(:tSemi)
+ return self.new(type,name,len).set_line(line)
+ end
+end
+class MessageStmt < QStmt
+ def initialize(name,suite)
+ @name = name
+ @suite = suite
+ end
+ def q_eval(locals)
+ group = Target::MessageDec.new(@name)
+ locals.register(group)
+ @suite.each do |stmt|
+ stmt.q_eval(locals.bind(group))
+ end
+ return group
+ end
+ def self.parse(tokens)
+ name = tokens.expect(:tWord).data
+ values = []
+ tokens.expect(:tOpenB)
+ while(tokens.peak != :tCloseB)
+ values << MessageElementStmt.parse(tokens)
+ end
+ names = {}
+ values.each do |val|
+ if(names[val.name])
+ raise QSyntaxError.new(<<ERROR_MSG)
+Hey! duplicate name #{val.name.inspect} in your message declaration statement (message #{name}).
+\tI found them at: #{names[val.name].q_stack_name()} and #{val.q_stack_name()}.
+\tWot. Wot.
+ERROR_MSG
+ end
+ names[val.name] = val
+ end
+ tokens.expect(:tCloseB)
+ tokens.expect(:tSemi)
+ self.new(name,values)
+ end
+end
+class QueueStmt < QStmt
+ def initialize(type,name)
+ @type,@name = type,name
+ end
+ def q_eval(locals)
+ queue = Target::QueueDec.new(@type.lookup(locals),@name)
+ locals.register(queue)
+ locals.local.add_queue(queue) if(locals.local.respond_to?(:add_queue))
+ return queue
+ end
+ def self.parse(tokens)
+ line = tokens.pos
+ type_name = QualifiedName.parse(tokens)
+ name = tokens.expect(:tWord).data
+ tokens.expect(:tSemi)
+ return self.new(type_name,name).set_line(line)
+ end
+end
diff --git a/aos/build/queues/objects/queue_group.rb b/aos/build/queues/objects/queue_group.rb
new file mode 100644
index 0000000..136834f
--- /dev/null
+++ b/aos/build/queues/objects/queue_group.rb
@@ -0,0 +1,115 @@
+class QueueGroupTypeStmt < QStmt
+ def initialize(name,suite)
+ @name,@suite = name,suite
+ end
+ def q_eval(locals)
+ group = Target::QueueGroupDec.new(@name)
+ group.created_by = self
+ locals.register(group)
+ @suite.each do |stmt|
+ stmt.q_eval(locals.bind(group))
+ end
+ return group
+ end
+end
+class ImplementsStmt < QStmt
+ def initialize(name)
+ @name = name
+ end
+ def q_eval(locals)
+
+ end
+ def self.parse(tokens)
+ name = QualifiedName.parse(tokens)
+ tokens.expect(:tSemi)
+ return self.new(name)
+ end
+end
+class QueueGroupStmt < QStmt
+ def initialize(type,name)
+ @type,@name = type,name
+ end
+ def q_eval(locals)
+ group = Target::QueueGroup.new(@type.lookup(locals),@name)
+ group.created_by = self
+ locals.register(group)
+ return group
+ end
+ def self.parse(tokens)
+ line = tokens.pos
+ type_name = QualifiedName.parse(tokens)
+ if(type_name.names.include?("queue_group"))
+ tokens.qError(<<ERROR_MSG)
+I was looking at the identifier you gave
+\tfor the queue group type between line #{line} and #{tokens.pos}
+\tThere shouldn't be a queue_group type called queue_group
+\tor including queue_group in it's path, it is a reserved keyword.
+\tWot. Wot.
+ERROR_MSG
+ end
+ if(tokens.peak == :tOpenB)
+ if(type_name.is_simple?())
+ type_name = type_name.to_simple
+ else
+ tokens.qError(<<ERROR_MSG)
+You gave the name: "#{type_name.to_s}" but you're only allowed to
+\thave simple names like "#{type_name.names[-1]}" in queue_group definitions
+\ttry something like:
+\tqueue_group ControlLoop { }
+\tWot. Wot.
+ERROR_MSG
+ end
+ tokens.expect(:tOpenB)
+ suite = []
+ while(tokens.peak != :tCloseB)
+ token = tokens.expect(:tWord) do |token|
+ <<ERROR_MSG
+I'm a little confused, I found a #{token.humanize} at #{token.pos}
+\tbut what I really wanted was an identifier signifying a nested
+\tmessage declaration, or queue definition, or an impliments statement.
+\tWot.Wot
+ERROR_MSG
+ end
+ case token.data
+ when "message"
+ suite << MessageStmt.parse(tokens)
+ when "queue"
+ suite << QueueStmt.parse(tokens)
+ when "implements"
+ suite << ImplementsStmt.parse(tokens)
+ else
+ tokens.qError(<<ERROR_MSG)
+expected a "queue","implements" or "message" statement rather
+\tthan a #{token.data.inspect}.
+\tWot. Wot.
+ERROR_MSG
+ end
+ end
+ tokens.expect(:tCloseB)
+ obj = QueueGroupTypeStmt.new(type_name,suite).set_line(line)
+ else
+ name = (tokens.expect(:tWord) do |token|
+ <<ERROR_MSG
+I found a #{token.humanize} at #{token.pos}
+\tbut I was in the middle of parsing a queue_group statement, and
+\twhat I really wanted was an identifier to store the queue group.
+\tSomething like: queue_group control_loops.Drivetrain my_cool_group;
+\tWot.Wot
+ERROR_MSG
+ end).data
+ obj = QueueGroupStmt.new(type_name,name).set_line(line)
+ if(tokens.peak == :tDot)
+ tokens.qError(<<ERROR_MSG)
+Hey! It looks like you're trying to use a complex identifier at: #{tokens.pos}
+\tThats not going to work. Queue Group definitions have to be of the form:
+\tqueue_group ComplexID SimpleID
+\tWot. Wot.
+ERROR_MSG
+ end
+ end
+ tokens.expect(:tSemi) do |token|
+ token.pos
+ end
+ return obj
+ end
+end
diff --git a/aos/build/queues/objects/tokenizer.rb b/aos/build/queues/objects/tokenizer.rb
new file mode 100644
index 0000000..2a33b90
--- /dev/null
+++ b/aos/build/queues/objects/tokenizer.rb
@@ -0,0 +1,213 @@
+class BufferedReader
+ def initialize(file)
+ @file = file
+ @line = 1
+ @chars = []
+ @col_nums = []
+ @col = 0
+ end
+ def filename
+ return File.basename(@file.path)
+ end
+ def pos()
+ "#{filename()}:#{lineno()},#{@col}"
+ end
+ def clear_comment()
+ @file.gets
+ @line += 1
+ end
+ def lineno()
+ return @line
+ return @file.lineno + 1
+ end
+ def pop_char()
+ val = @chars.pop() || @file.read(1)
+ @col_nums[@line] = @col += 1
+ if(val == "\n")
+ @line += 1
+ @col = 0
+ end
+
+ return val
+ end
+ def unpop_char(char)
+ if(char == "\n")
+ @line -= 1
+ @col = @col_nums[@line]
+ end
+ @col -= 1
+ @chars.push(char)
+ end
+end
+class Tokenizer
+ TOKEN_TYPES = {"{" => :tOpenB,"}"=> :tCloseB,";" => :tSemi,"," => :tComma,
+ "(" => :tOpenParan,")" => :tCloseParan,"=" => :tAssign,"." => :tDot,
+ "<<"=> :tLShift,"*" => :tMult,"+" => :tAdd,"[" => :tOpenB,
+ "]" => :tCloseB}
+ Humanize = TOKEN_TYPES.invert
+ class Token
+ attr_accessor :type,:data,:pos
+ def to_s
+ if(@type == :tString)
+ val = @data.inspect.to_s
+ elsif(@type == :tWord)
+ val = @data.to_s
+ else
+ val = @data.to_s
+ end
+ return "#{val.ljust(50)}:#{@type}"
+ end
+ def humanize()
+ if(@type == :tString)
+ return "#{@data.inspect.to_s} string"
+ elsif(@type == :tWord)
+ return "#{@data.inspect} identifier"
+ end
+ return Humanize[@type].inspect
+ end
+ def inspect()
+ data = ""
+ data = " #{@data.inspect}" if(@data)
+ "<Token :#{@type}#{data} at #{@pos}>"
+ end
+ def ==(other)
+ if(other.class == Symbol)
+ return @type == other
+ elsif(other.class == self.class)
+ return @type == other.type && @data == other.data
+ else
+ return nil
+ end
+ end
+ end
+ def initialize(file)
+ file = File.open(file,"r") if(file.class == String)
+ @read = BufferedReader.new(file)
+ end
+ def qError(error)
+ syntax_error(error)
+ end
+ def syntax_error(msg)
+ err = QSyntaxError.new(msg)
+ err.qstacktrace << "#{@read.lineno} of #{@read.filename}"
+ raise err
+ end
+ def peak_token()
+ @peak_token = next_token()
+ end
+ def peak()
+ peak_token()
+ end
+ def next()
+ next_token()
+ end
+ def pos()
+ @read.pos
+ end
+ def tokenize(string_token)
+ token = Token.new()
+ token.type = TOKEN_TYPES[string_token]
+ return token
+ end
+ def next_token()
+ if(token = @peak_token)
+ @peak_token = nil
+ return token
+ end
+ token = next_token_cache()
+ pos = self.pos()
+ token.pos = pos
+ return token
+ end
+ def next_token_cache()
+ token = Token.new()
+ token.data = ""
+ while (char = @read.pop_char())
+ #puts "#{char.inspect}:#{token.inspect}"
+ if(char == "/")
+ if(@read.pop_char == "/")
+ @read.clear_comment()
+ else
+ syntax_error("unexpected #{char.inspect}")
+ end
+ elsif(char == "#")
+ @read.clear_comment()
+ elsif(char =~ /[\s\r\n]/)
+ if(token.type)
+ return token
+ end
+ elsif(char =~ /\"/)
+ token.type = :tString
+ token.data = ""
+ while((char = @read.pop_char) != "\"")
+ token.data += char
+ end
+ return token
+ elsif(char =~ /[1-9]/)
+ token.type = :tNumber
+ token.data = char.to_i
+ while(char != ".")
+ char = @read.pop_char
+ if(char =~ /[0-9]/)
+ token.data = char.to_i + token.data * 10
+ elsif(char == ".")
+ else
+ @read.unpop_char(char)
+ return token
+ end
+ end
+ second_char = 0
+ man = 0
+ while(true)
+ char = @read.pop_char
+ if(char =~ /[0-9]/)
+ second_char = char.to_i + second_char * 10
+ man = man * 10
+ else
+ @read.unpop_char(char)
+ token.data += second_char / man.to_f
+ return token
+ end
+ end
+ elsif(char == ":")
+ if(@read.pop_char == "=")
+ return tokenize(":=")
+ end
+ syntax_error("unexpected \":\"")
+ elsif(char =~ /[;\{\}=()\",\*\+\.\[\]]/)
+ return(tokenize(char))
+ elsif(char =~ /[a-zA-Z_]/)
+ token.type = :tWord
+ token.data = char
+ while(true)
+ char = @read.pop_char()
+ if(char && char =~ /\w/)
+ token.data += char
+ else
+ @read.unpop_char(char)
+ return token
+ end
+ end
+ elsif(char == "<")
+ if((char = @read.pop_char()) == "<")
+ return tokenize("<<")
+ else
+ @read.unpop_char(char)
+ return tokenize("<")
+ end
+ else
+ syntax_error("unexpected #{char.inspect}")
+ end
+ end
+ token.type = :tEnd
+ return token
+ end
+ def expect(type,&blk)
+ token = self.next
+ if(token != type)
+ syntax_error(blk.call(token)) if(blk)
+ syntax_error("unexpected: #{token.type}")
+ end
+ return token
+ end
+end
diff --git a/aos/build/queues/output/message_dec.rb b/aos/build/queues/output/message_dec.rb
new file mode 100644
index 0000000..0e957be
--- /dev/null
+++ b/aos/build/queues/output/message_dec.rb
@@ -0,0 +1,277 @@
+require "sha1"
+class Target::MessageDec < Target::Node
+ attr_accessor :name,:loc,:parent,:msg_hash
+ def initialize(name)
+ @name = name
+ @members = []
+ end
+ def extern=(value)
+ @extern=value
+ end
+ def get_name()
+ if(@parent)
+ return "#{@parent.get_name}.#{@name}"
+ else
+ return "#{@name}"
+ end
+ end
+ def add_member(member)
+ @members << member
+ end
+ def create_Print(type_class,cpp_tree)
+ member_func = CPP::MemberFunc.new(type_class,"size_t","Print")
+ type_class.add_member(member_func)
+ member_func.args << "char *buffer"
+ member_func.args << "size_t length"
+ member_func.const = true
+ format = "\""
+ args = []
+ @members.each do |elem|
+ format += ", "
+ format += elem.toPrintFormat()
+ if (elem.type == 'bool')
+ args.push("#{elem.name} ? 't' : 'f'")
+ else
+ args.push(elem.name)
+ end
+ end
+ format += "\""
+ member_func.suite << "size_t super_size = ::aos::Message::Print(buffer, length)"
+ member_func.suite << "buffer += super_size"
+ member_func.suite << "length -= super_size"
+ member_func.suite << "return super_size + snprintf(buffer, length, " + ([format] + args).join(", ") + ")";
+ end
+ def create_Serialize(type_class,cpp_tree)
+ member_func = CPP::MemberFunc.new(type_class,"size_t","Serialize")
+ type_class.add_member(member_func)
+ #cpp_tree.cc_file.add_funct(member_func)
+ member_func.args << "char *buffer"
+ member_func.suite << "::aos::Message::Serialize(buffer)"
+ member_func.const = true
+ offset = 0
+ @members.each do |elem|
+ elem.toNetwork(offset,member_func.suite)
+ offset += elem.size;
+ end
+ member_func.suite << "return Size()"
+ end
+ def create_Deserialize(type_class,cpp_tree)
+ member_func = CPP::MemberFunc.new(type_class,"size_t","Deserialize")
+ type_class.add_member(member_func)
+ #cpp_tree.cc_file.add_funct(member_func)
+ member_func.args << "const char *buffer"
+ member_func.suite << "::aos::Message::Deserialize(buffer)"
+ offset = 0
+ @members.each do |elem|
+ elem.toHost(offset,member_func.suite)
+ offset += elem.size;
+ end
+ member_func.suite << "return Size()"
+ end
+ def create_Zero(type_class,cpp_tree)
+ member_func = CPP::MemberFunc.new(type_class,"void","Zero")
+ type_class.add_member(member_func)
+ #cpp_tree.cc_file.add_funct(member_func)
+ @members.each do |elem|
+ elem.zeroCall(member_func.suite)
+ end
+ member_func.suite << "::aos::Message::Zero()"
+ end
+ def create_Size(type_class,cpp_tree)
+ member_func = CPP::MemberFunc.new(type_class,"size_t","Size")
+ member_func.inline = true
+ member_func.static = true
+ type_class.add_member(member_func.forward_dec)
+ #cpp_tree.cc_file.add_funct(member_func)
+ size = 0
+ @members.each do |elem|
+ size += elem.size
+ end
+ member_func.suite << CPP::Return.new(CPP::Add.new(size,
+ "::aos::Message::Size()"))
+ end
+ def self.builder_loc(loc)
+ return @builder_loc if(@builder_loc)
+ return @builder_loc = loc.root.get_make("aos")
+ end
+ def type_name(builder_loc,name)
+ if(builder_loc == @loc) #use relative name
+ return name
+ else #use full name
+ return @loc.to_cpp_id(name)
+ end
+ end
+ def create(cpp_tree)
+ return self if(@extern)
+ orig_namespace = namespace = cpp_tree.get(@loc)
+ name = ""
+ if(namespace.class < Types::Type) #is nested
+ name = namespace.name + "_" + name
+ namespace = namespace.space
+ end
+ type_class = namespace.add_struct(name + @name)
+ if(name.length > 0)
+ orig_namespace.add_member(:public, Types::TypeDef.new(type_class,@name))
+ end
+ cpp_tree.set(self,type_class)
+ type_class.set_parent("public ::aos::Message")
+ ts = (@members.collect { |elem|
+ elem.type + " " + elem.name
+ }).join(";")
+ self.msg_hash = "0x#{SHA1.hexdigest(ts)[-8..-1]}"
+ type_class.add_member("enum {kQueueLength = 1234, kHash = #{self.msg_hash}}")
+ @members.each do |elem|
+ type_class.add_member(elem.create_usage(cpp_tree))
+ end
+
+ create_Serialize(type_class,cpp_tree)
+ create_Deserialize(type_class,cpp_tree)
+ create_Zero(type_class,cpp_tree)
+ create_Size(type_class,cpp_tree)
+ create_Print(type_class,cpp_tree)
+
+ b_namespace = cpp_tree.get(b_loc = self.class.builder_loc(@loc))
+
+ safetemplate = Types::TemplateClass.new(b_namespace,"SafeMessageBuilder")
+ ifdef_statement = Types::PreprocessorIf.new(b_namespace,"!defined(__VXWORKS__) && !defined(__TEST_VXWORKS__)")
+ ifdef_statement.add_member(safetemplate)
+ b_namespace.add(ifdef_statement)
+ template = b_namespace.add_template("MessageBuilder")
+ safetemplate.spec_args << t = @loc.to_cpp_id(@name)
+ template.spec_args << t = @loc.to_cpp_id(@name)
+ safemsg_ptr_t = "SafeScopedMessagePtr< #{t}>"
+ msg_ptr_t = "ScopedMessagePtr< #{t}>"
+ safemsg_bld_t = "SafeMessageBuilder< #{t}>"
+ msg_bld_t = "MessageBuilder< #{t}>"
+ safetemplate.add_member(:private,"#{safemsg_ptr_t} msg_ptr_")
+ template.add_member(:private,"#{msg_ptr_t} msg_ptr_")
+ namespace.add_pre_swig("%feature(\"valuewrapper\") #{safemsg_bld_t}")
+ template.add_member(:private,"#{msg_bld_t}(const #{msg_bld_t}&)")
+ template.add_member(:private,"void operator=(const #{msg_bld_t}&)")
+ safetemplate.add_member(:private,"friend class ::aos::Queue< #{t}>")
+ template.add_member(:private,"friend class ::aos::Queue< #{t}>")
+
+ cons = CPP::Constructor.new(template)
+ unsafe_cons = CPP::Constructor.new(template)
+ cons_ifdef_statement = CPP::PreprocessorIf.new(cons, unsafe_cons)
+ cons_ifdef_statement.name = "!defined(__VXWORKS__) && !defined(__TEST_VXWORKS__)"
+ template.add_member(:private,cons_ifdef_statement)
+ cons.args << "aos_queue *queue"
+ cons.args << "#{t} *msg"
+ unsafe_cons.args << "#{t} *msg"
+ cons.add_cons("msg_ptr_","queue","msg")
+ unsafe_cons.add_cons("msg_ptr_","msg")
+ cons = safetemplate.add_member(:private,CPP::Constructor.new(safetemplate))
+ cons.args << "aos_queue *queue"
+ cons.add_cons("msg_ptr_","queue")
+ safetemplate.public
+ template.public
+ DefineMembers(cpp_tree, safetemplate, safemsg_bld_t)
+ DefineMembers(cpp_tree, template, msg_bld_t)
+
+ java_type_name = java_type_name(cpp_tree)
+ namespace.add_post_swig("%template(#{java_type_name}) ::aos::Queue< #{t}>")
+ namespace.add_post_swig("%template(#{java_ptr_name(cpp_tree)}) ::aos::SafeScopedMessagePtr< #{t}>")
+ namespace.add_post_swig("%template(#{java_builder_name(cpp_tree)}) ::aos::SafeMessageBuilder< #{t}>")
+ # TODO(aschuh): Figure out why this doesn't work and fix it.
+ #namespace.add_post_swig("%typemap(javabase) #{@name} \"aos.Message\"")
+
+ end
+ def DefineMembers(cpp_tree, template, msg_bld_t)
+ send = template.def_func("bool","Send")
+ send.suite << CPP::Return.new("msg_ptr_.Send()")
+ @members.each do |elem|
+=begin
+ MessageBuilder<frc971::control_loops::Drivetrain::Goal> &steering(
+ double steering) {
+ msg_ptr_->steering = steering;
+ return *this;
+ }
+=end
+ setter = template.def_func(msg_bld_t,"&#{elem.name}")
+ setter.args << elem.create_usage(cpp_tree)
+ elem.set_message_builder(setter.suite)
+ setter.suite << CPP::Return.new("*this")
+
+ end
+ end
+ def java_ptr_name(cpp_tree)
+ return "#{@name}MessagePtr"
+ end
+ def java_builder_name(cpp_tree)
+ return "#{@name}MessageBuilder"
+ end
+ def java_type_name(cpp_tree)
+ return "#{@name}Queue"
+ end
+end
+class Target::MessageElement < Target::Node
+ attr_accessor :name,:loc,:size,:zero,:type,:printformat
+ def initialize(type,name)
+ @type,@name = type,name
+ end
+ def toPrintFormat()
+ return printformat
+ end
+ def create_usage(cpp_tree)
+ "#{@type} #{@name}"
+ end
+ def toNetwork(offset,suite)
+ offset = (offset == 0) ? "" : "#{offset} + "
+ suite << f_call = CPP::FuncCall.build("to_network",
+ "&#{@name}",
+ "&buffer[#{offset}::aos::Message::Size()]")
+ f_call.args.dont_wrap = true
+ end
+ def toHost(offset,suite)
+ offset = (offset == 0) ? "" : "#{offset} + "
+ suite << f_call = CPP::FuncCall.build("to_host",
+ "&buffer[#{offset}::aos::Message::Size()]",
+ "&#{@name}")
+ f_call.args.dont_wrap = true
+ end
+ def set_message_builder(suite)
+ suite << "msg_ptr_->#{@name} = #{@name}"
+ end
+
+ def zeroCall(suite)
+ suite << CPP::Assign.new(@name,@zero)
+ end
+end
+class Target::MessageArrayElement < Target::Node
+ attr_accessor :name,:loc,:size,:zero,:type
+ def initialize(type,name,length)
+ @type,@name,@length = type,name,length
+ end
+ def create_usage(cpp_tree)
+ "#{@type} #{@name}[#@length]"
+ end
+ def type()
+ "#{@type}[#@length]"
+ end
+ def size()
+ @size * @length
+ end
+ def toNetwork(offset,suite)
+ offset = (offset == 0) ? "" : "#{offset} + "
+ suite << for_stmt = CPP::For.new("int i = 0","i < #{@length}","i++")
+ for_stmt.suite << f_call = CPP::FuncCall.build("to_network",
+ "&(#{@name}[i])",
+ "&buffer[i + #{offset}::aos::Message::Size()]")
+ f_call.args.dont_wrap = true
+ end
+ def toHost(offset,suite)
+ offset = (offset == 0) ? "" : "#{offset} + "
+ suite << for_stmt = CPP::For.new("int i = 0","i < #{@length}","i++")
+ for_stmt.suite << f_call = CPP::FuncCall.build("to_host",
+ "&buffer[i + #{offset}::aos::Message::Size()]",
+ "&(#{@name}[i])")
+ f_call.args.dont_wrap = true
+ end
+ def set_message_builder(suite)
+ suite << "memcpy(msg_ptr_->#{@name},#{@name},#@length)"
+ end
+ def zeroCall(suite)
+ suite << "memset(#@name,0,#{size()})"
+ end
+end
diff --git a/aos/build/queues/output/q_file.rb b/aos/build/queues/output/q_file.rb
new file mode 100644
index 0000000..af76ee1
--- /dev/null
+++ b/aos/build/queues/output/q_file.rb
@@ -0,0 +1,187 @@
+require "sha1"
+module Target
+end
+class Target::Node
+ attr_accessor :created_by
+end
+class Target::QFile < Target::Node
+ def initialize() #needs to know repo_path,
+ @class_types = []
+ end
+ def add_type(type)
+ @class_types << type
+ end
+ def extern=(value)
+ @class_types.each do |type|
+ type.extern=value
+ end
+ end
+ def make_cpp_tree(rel_path)
+ cpp_tree = DepFilePair.new(rel_path)
+ cpp_tree.add_header_include("\"aos/common/macros.h\"")
+ cpp_tree.add_header_include("\"aos/common/queue.h\"")
+ @class_types.each do |type|
+ cpp_tree.get(type)
+ end
+ return cpp_tree
+ end
+end
+class Target::QInclude < Target::Node
+ def initialize(path)
+ @path = path
+ end
+ def create(cpp_tree)
+# inc = cpp_tree.header.add_include("\"#{@path}\"")
+ inc = cpp_tree.add_header_include("\"#{@path}\"")
+ cpp_tree.set(self,inc)
+ end
+end
+class Target::QueueGroupDec < Target::Node
+ attr_accessor :name,:loc,:parent,:queues
+ def initialize(name)
+ @name = name
+ @queues = []
+ @subs = {}
+ end
+ def root()
+ @parent.root()
+ end
+ def []=(key,val)
+ #puts "#{key}= #{val}"
+ @subs[key] = val
+ end
+ def extern=(value)
+ @extern=value
+ end
+ def get_name()
+ if(@parent)
+ return "#{@parent.get_name}.#{@name}"
+ else
+ return "#{@name}"
+ end
+ end
+ def to_cpp_id(id)
+ name = "#{@name}::#{id}"
+ return @parent.to_cpp_id(name) if(@parent)
+ return name
+ end
+ def [](key)
+ #puts "#{key}"
+ @subs[key]
+ end
+ def add_queue(queue)
+ @queues.push(queue)
+ end
+ def hash_with_name(name)
+ ts = (@queues.collect { |queue|
+ queue.msg_hash()
+ }).join("") + name
+ return "0x#{SHA1.hexdigest(ts)[-8..-1]}"
+ end
+ def create(cpp_tree)
+ return if(@extern)
+ namespace = cpp_tree.get(@loc)
+ type_class = Types::Class.new(namespace,@name)
+ cpp_tree.set(self,type_class) #breaks infinite recursion
+ type_class.set_parent("public ::aos::QueueGroup")
+ @queues.each do |queue|
+ type_class.add_member(:public,queue.create_usage(cpp_tree))
+ namespace.add_pre_swig("%immutable #{@name}::#{queue.name}")
+ end
+ create_Constructor(type_class,cpp_tree)
+ namespace.add(type_class)
+ end
+ def create_Constructor(type_class,cpp_tree)
+ member_func = CPP::Constructor.new(type_class)
+ type_class.add_member(:public,member_func)
+ #cpp_tree.cc_file.add_funct(member_func)
+ member_func.args << "const char *name";
+ member_func.args << "uint32_t hash";
+ member_func.add_cons("::aos::QueueGroup","name", "hash")
+ @queues.each do |queue|
+ member_func.args << "const char *#{queue.name}_name";
+ member_func.add_cons(queue.name,"#{queue.name}_name")
+ end
+ end
+end
+class Target::QueueGroup < Target::Node
+ attr_accessor :name,:loc
+ def initialize(type,name)
+ @type,@name = type,name
+ end
+ def type_name()
+ if(@type.loc == @loc) #use relative name
+ return @type.name
+ else #use full name
+ return @type.loc.to_cpp_id(@type.name)
+ end
+ end
+ def create(cpp_tree)
+ namespace = cpp_tree.get(@loc)
+ type = cpp_tree.get(@type)
+ cpp_tree.set(self,self)
+ namespace.add_cc("static #{type_name} *#{@name}_ptr")
+ counter = "#{@name}_counter"
+ namespace.add_cc("static int #{counter}")
+
+ str = <<COMMENT_END
+Schwarz counter to construct and destruct the #{@name} object.
+Must be constructed before &#{@name} is constructed so that #{@name}_ptr
+is valid so we can store a reference to the object.
+COMMENT_END
+ str.split(/\n/).each do |str_sec|
+ namespace.class_comment(str_sec)
+ end
+ init_class = namespace.add_class("InitializerFor_" + @name).add_dep(type)
+
+
+ init_class.add_cc_comment(
+ "The counter is initialized at load-time, i.e., before any of the static",
+ "objects are initialized.")
+
+
+ cons = CPP::Constructor.new(init_class)
+ init_class.add_member(:public,cons)
+ cons.suite << if_stmt = CPP::If.new("0 == #{counter}++")
+ if_stmt.suite << "printf(#{"making a #{@name}!\n".inspect})"
+
+ cons_call = CPP::FuncCall.new("new #{type_name}")
+ cons_call.args.push(@loc.queue_name(@name).inspect)
+
+ cons_call.args.push(@type.hash_with_name(@loc.queue_name(@name).inspect))
+ @type.queues.collect do |queue|
+ cons_call.args.push(@loc.queue_name(@name + "." + queue.name).inspect)
+ end
+ if_stmt.suite << CPP::Assign.new("#{@name}_ptr",cons_call)
+ if_stmt.else_suite << CPP::FuncCall.build("printf","already made a #{@name}\n".inspect)
+
+
+ destruct = CPP::Destructor.new(init_class)
+ destruct.suite << if_stmt = CPP::If.new("0 == --#{counter}")
+ if_stmt.suite << "printf(#{"deleting a #{@name}!! :) !!\n".inspect})"
+ if_stmt.suite << "delete #{@name}_ptr"
+ if_stmt.suite << CPP::Assign.new("#{@name}_ptr","NULL")
+
+ init_class.add_member(:public,destruct)
+ init_class.static = true
+ init_class.dec = @name + "_initializer";
+
+ str = <<COMMENT_END
+Create a reference to the new object in the pointer. Since we have already
+created the initializer
+COMMENT_END
+ comments = str.split(/\n/).map{|str_sec| CPP::Comment.new(str_sec)}
+ comments << "static UNUSED_VARIABLE #{type_name} &#{@name} = " +
+ "#{@name}_initializer.get()"
+ namespace.add_post_swig("%immutable #{@name}_initializer")
+ namespace.add_post_swig(CPP::SwigPragma.new("java", "modulecode", CPP::Suite.new(["public static final #{@name} = get#{@name.capitalize}_initializer().get()"])))
+ ifdef_statement = CPP::IfnDef.new(CPP::Suite.new(comments))
+ ifdef_statement.name = "SWIG"
+ namespace.add(ifdef_statement)
+
+
+ get = init_class.def_func(type_name,"get") #.add_dep(type)
+ get.pre_func_types = "&"
+ get.suite << CPP::Return.new("*#{@name}_ptr")
+ end
+end
diff --git a/aos/build/queues/output/queue_dec.rb b/aos/build/queues/output/queue_dec.rb
new file mode 100644
index 0000000..8c3bd51
--- /dev/null
+++ b/aos/build/queues/output/queue_dec.rb
@@ -0,0 +1,104 @@
+class Target::QueueDec < Target::Node
+ attr_accessor :name,:loc
+ def initialize(type,name)
+ @type,@name = type,name
+ end
+ def msg_hash()
+ return @type.msg_hash
+ end
+ def java_type_name(cpp_tree)
+ type = cpp_tree.get(@type)
+ return "#{type.name}Queue"
+ end
+ def full_message_name(cpp_tree)
+ type = cpp_tree.get(@type)
+ return @type.loc.to_cpp_id(type.name)
+ end
+ def full_ptr_name(cpp_tree)
+ return "::aos::SafeScopedMessagePtr< #{full_message_name(cpp_tree)}>"
+ end
+ def full_builder_name(cpp_tree)
+ return "::aos::MessageBuilder< #{full_message_name(cpp_tree)}>"
+ end
+ def full_type_name(cpp_tree)
+ return "::aos::Queue< #{full_message_name(cpp_tree)}>"
+ end
+ def type_name(cpp_tree,queue_type = "::aos::Queue")
+ type = cpp_tree.get(@type)
+ if(@type.loc == @loc) #use relative name
+ return "#{queue_type}<#{type.name}>"
+ else #use full name
+ return "#{queue_type}< #{@type.loc.to_cpp_id(type.name)}>"
+ end
+ end
+ def create_usage(cpp_tree)
+ "#{type_name(cpp_tree)} #{@name}"
+ end
+ def create(cpp_tree)
+ namespace = cpp_tree.get(@loc)
+ type = cpp_tree.get(@type)
+ cpp_tree.set(self,self)
+ type_name = type_name(cpp_tree)
+ full_type_name = full_type_name(cpp_tree)
+ namespace.add_cc("static #{type_name} *#{@name}_ptr")
+ counter = "#{@name}_counter"
+ namespace.add_cc("static int #{counter}")
+
+ str = <<COMMENT_END
+Schwarz counter to construct and destruct the #{@name} queue.
+Must be constructed before &#{@name} is constructed so that #{@name}_ptr
+is valid so we can store a reference to the object.
+COMMENT_END
+ str.split(/\n/).each do |str_sec|
+ namespace.class_comment(str_sec)
+ end
+ init_class = namespace.add_class("InitializerFor_" + @name)
+
+ init_class.add_cc_comment(
+ "The counter is initialized at load-time, i.e., before any of the static",
+ "objects are initialized.")
+
+
+ cons = CPP::Constructor.new(init_class)
+ init_class.add_member(:public,cons)
+ cons.suite << if_stmt = CPP::If.new("0 == #{counter}++")
+ if_stmt.suite << "printf(#{"making a #{@name} queue!\n".inspect})"
+
+ cons_call = CPP::FuncCall.new("new #{type_name}")
+ cons_call.args.push(@loc.queue_name(@name).inspect)
+ if_stmt.suite << CPP::Assign.new("#{@name}_ptr",cons_call)
+ if_stmt.else_suite << CPP::FuncCall.build("printf","already made a #{@name}\n".inspect)
+
+
+ destruct = CPP::Destructor.new(init_class)
+ init_class.add_member(:public,destruct)
+ destruct.suite << if_stmt = CPP::If.new("0 == --#{counter}")
+ if_stmt.suite << "printf(#{"deleting a #{@name}!! :) !!\n".inspect})"
+ if_stmt.suite << "delete #{@name}_ptr"
+ if_stmt.suite << CPP::Assign.new("#{@name}_ptr","NULL")
+
+ init_class.static = true
+ init_class.dec = @name + "_initializer";
+
+ str = <<COMMENT_END
+Create a reference to the new object in the pointer. Since we have already
+created the initializer
+COMMENT_END
+ comments = str.split(/\n/).map{|str_sec| CPP::Comment.new(str_sec)}
+ comments << "static UNUSED_VARIABLE #{type_name} &#{@name} = " +
+ "#{@name}_initializer.get()"
+ namespace.add_post_swig("%immutable #{@name}_initializer")
+ java_type_name = java_type_name(cpp_tree)
+ namespace.add_post_swig(CPP::SwigPragma.new("java", "modulecode", CPP::Suite.new(["public static final #{java_type_name} #{@name} = get#{@name.capitalize}_initializer().get()"])))
+
+ ifdef_statement = CPP::IfnDef.new(CPP::Suite.new(comments))
+ ifdef_statement.name = "SWIG"
+ namespace.add(ifdef_statement)
+
+ get = init_class.def_func(full_type_name,"get")
+ get.pre_func_types = "&"
+ get.suite << CPP::Return.new("*#{@name}_ptr")
+
+ end
+end
+
diff --git a/aos/build/swig.gypi b/aos/build/swig.gypi
new file mode 100644
index 0000000..2e99a95
--- /dev/null
+++ b/aos/build/swig.gypi
@@ -0,0 +1,73 @@
+# Include this file in any target that needs to use swig wrappers.
+#
+# To use, create a target of the following form:
+# {
+# 'target_name': 'my_target_javawrap',
+# 'type': 'static_library', # or any other type that can handle .cc files
+# 'sources': [
+# 'aos/example/target.swig',
+# ],
+# 'variables': {
+# 'package': 'aos.test',
+# },
+# 'includes': ['path/to/swig.gypi'],
+# },
+# Code that depends on this target will be able to use the swig wrapped
+# java classes.
+#
+# using <http://src.chromium.org/svn/trunk/src/build/protoc.gypi> as an
+# example of how this should work
+{
+ 'variables': {
+ 'prefix_dir': '<(SHARED_INTERMEDIATE_DIR)/',
+ 'out_dir': '<(prefix_dir)/<(_target_name)/',
+ 'output_java_wrap': '<(out_dir)/<(RULE_INPUT_ROOT)_wrap.cc',
+ 'java_dir': '<(out_dir)/<(RULE_INPUT_ROOT)_java',
+ 'no_rsync': 1,
+ },
+ 'rules': [
+ {
+ 'rule_name': 'genswig',
+ 'extension': 'swig',
+ 'outputs': [
+ '<(output_java_wrap)',
+ '<(java_dir)',
+ ],
+ 'action': [
+ '<(DEPTH)/aos/build/mkdirswig',
+ '<(java_dir)',
+ '-I<(DEPTH)',
+ '-outdir', ' <(java_dir)',
+ '-package', '<(package)',
+ '-o', '<(output_java_wrap)',
+ '-c++',
+ '-Wall',
+ '-Wextra',
+ '-java',
+ '<(RULE_INPUT_PATH)'],
+ 'message': 'Generating C++ code from <(RULE_INPUT_DIRNAME)/<(RULE_INPUT_ROOT).swig',
+ 'process_outputs_as_sources': 1,
+ },
+ ],
+ 'cflags': [
+# For the swig-generated C++ code.
+ '-fno-strict-aliasing',
+ '-Wno-cast-qual',
+ ],
+ 'include_dirs': [
+ '<(prefix_dir)/<(_target_name)',
+ '/usr/lib/jvm/default-java/include',
+ '/usr/lib/jvm/default-java/include/linux',
+ ],
+ 'direct_dependent_settings': {
+ 'include_dirs': [
+ '<(prefix_dir)/<(_target_name)',
+ '/usr/lib/jvm/default-java/include',
+ '/usr/lib/jvm/default-java/include/linux',
+ ],
+ 'variables': {
+ 'gen_srcdir_parents': ['<(out_dir)'],
+ },
+ },
+ 'hard_dependency': 1,
+}
diff --git a/aos/common/Configuration.cpp b/aos/common/Configuration.cpp
new file mode 100644
index 0000000..e0b56ea
--- /dev/null
+++ b/aos/common/Configuration.cpp
@@ -0,0 +1,150 @@
+#include "Configuration.h"
+
+#include <stdio.h>
+#include <string.h>
+#include <errno.h>
+#include <stdlib.h>
+#include <stdarg.h>
+#include <sys/types.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+#ifdef __VXWORKS__
+#include <ifLib.h>
+#include <inetLib.h>
+#else
+#include <ifaddrs.h>
+#endif
+
+#include "aos/aos_core.h"
+#ifndef __VXWORKS__
+#include "aos/common/unique_malloc_ptr.h"
+#endif
+
+namespace aos {
+namespace configuration {
+
+namespace {
+
+#ifdef __VXWORKS__
+const size_t kMaxAddrLength = INET_ADDR_LEN;
+#else
+// Including the terminating '\0'.
+const size_t kMaxAddrLength = 18;
+#endif
+// Returns whether or not the current IP address is in ownIPAddress.
+bool GetOwnIPAddress();
+
+#ifdef __VXWORKS__
+// vxworks doesn't have real asprintf.......
+static inline int aos_asprintf(size_t max_len, char **strp, const char *fmt, ...) {
+ *strp = static_cast<char *>(malloc(max_len));
+ if (*strp == NULL) {
+ return -1;
+ }
+ va_list argp;
+ va_start(argp, fmt);
+ const int r = vsnprintf(*strp, max_len, fmt, argp);
+ va_end(argp);
+ if (static_cast<uintmax_t>(r) >= max_len) {
+ errno = EOVERFLOW;
+ free(*strp);
+ return -1;
+ }
+ return r;
+}
+
+// 4-slot cRIO: motfec0
+// 8-slot cRIO port 1: fec0
+// ifShow will show you all of the ones on a cRIO
+const char *const kCrioNetInterfaces[] = {"fec0", "motfec0"};
+bool GetOwnIPAddress(char *buffer, size_t bufferSize) {
+ if (bufferSize < INET_ADDR_LEN) {
+ LOG(ERROR, "bufferSize(%jd) isn't >= INET_ADDR_LEN(%jd)\n",
+ static_cast<intmax_t>(bufferSize),
+ static_cast<intmax_t>(INET_ADDR_LEN));
+ return false;
+ }
+ for (size_t i = 0;
+ i < sizeof(kCrioNetInterfaces) / sizeof(kCrioNetInterfaces[0]); ++i) {
+ if (ifAddrGet(const_cast<char *>(kCrioNetInterfaces[i]), buffer) != OK) {
+ LOG(DEBUG, "ifAddrGet(\"%s\", %p) failed with %d: %s\n",
+ kCrioNetInterfaces[i], buffer, errno, strerror(errno));
+ } else {
+ return true;
+ }
+ }
+ LOG(ERROR, "couldn't get the cRIO's IP address\n");
+ return false;
+}
+#else
+static inline int aos_asprintf(size_t, char **strp, const char *fmt, ...) {
+ va_list argp;
+ va_start(argp, fmt);
+ const int r = vasprintf(strp, fmt, argp);
+ va_end(argp);
+ return r;
+}
+
+const char *const kAtomNetInterface = "eth0";
+bool GetOwnIPAddress(char *buffer, size_t bufferSize) {
+ ifaddrs *addrs;
+ if (getifaddrs(&addrs) != 0) {
+ LOG(ERROR, "getifaddrs(%p) failed with %d: %s\n", &addrs,
+ errno, strerror(errno));
+ return false;
+ }
+ // Smart pointers don't work very well for iterating through a linked list,
+ // but it does do a very nice job of making sure that addrs gets freed.
+ unique_c_ptr<ifaddrs, freeifaddrs> addrs_deleter(addrs);
+
+ for (; addrs != NULL; addrs = addrs->ifa_next) {
+ if (addrs->ifa_addr->sa_family == AF_INET) {
+ if (strcmp(kAtomNetInterface, addrs->ifa_name) == 0) {
+ const char *ipAddress = inet_ntoa(
+ reinterpret_cast<sockaddr_in *>(addrs->ifa_addr)->sin_addr);
+ strncpy(buffer, ipAddress, bufferSize);
+ return true;
+ }
+ }
+ }
+ LOG(ERROR, "couldn't find an AF_INET interface named \"%s\"\n",
+ kAtomNetInterface);
+ return false;
+}
+#endif
+
+const char *RawIPAddress(uint8_t last_part) {
+ char ownIPAddress[kMaxAddrLength];
+ if (!GetOwnIPAddress(ownIPAddress, sizeof(ownIPAddress))) {
+ return NULL;
+ }
+ char *last_dot = strrchr(ownIPAddress, '.');
+ if (last_dot == NULL) {
+ LOG(ERROR, "can't find any '.'s in \"%s\"\n", ownIPAddress);
+ return NULL;
+ }
+ *last_dot = '\0';
+
+ char *r;
+ if (aos_asprintf(kMaxAddrLength, &r, "%s.%hhu",
+ ownIPAddress, last_part) == -1) {
+ return NULL;
+ }
+ return r;
+}
+
+} // namespace
+
+const char *GetIPAddress(NetworkDevice device) {
+ switch (device) {
+ case NetworkDevice::kAtom:
+ return RawIPAddress(179);
+ case NetworkDevice::kCRIO:
+ return RawIPAddress(2);
+ }
+ LOG(FATAL, "Unknown network device.");
+ return NULL;
+}
+
+} // namespace configuration
+} // namespace aos
diff --git a/aos/common/Configuration.h b/aos/common/Configuration.h
new file mode 100644
index 0000000..bf2dc80
--- /dev/null
+++ b/aos/common/Configuration.h
@@ -0,0 +1,42 @@
+#ifndef AOS_COMMON_CONFIGURATION_H_
+#define AOS_COMMON_CONFIGURATION_H_
+
+#include "aos/aos_stdint.h"
+
+namespace aos {
+
+// Constants representing the various ports used for communications and some
+// documentation about what each is used for.
+enum class NetworkPort : uint16_t {
+ // UDP socket sending motor values from the atom to the crio.
+ kMotors = 9710,
+ // UDP socket forwarding drivers station packets from the crio to the atom.
+ kDS = 9711,
+ // UDP socket sending sensor values from the crio to the atom.
+ kSensors = 9712,
+ // TCP socket(s) (automatically reconnects) sending logs from the crio to the
+ // atom.
+ kLogs = 9713,
+ // HTTP server that sends out camera feeds in mjpg format.
+ // Should not be changed because this number shows up elsewhere too.
+ kCameraStreamer = 9714,
+};
+
+// Holds global configuration data. All of the public static functions are safe
+// to call concurrently (the ones that need to create locks on the cRIO).
+namespace configuration {
+
+// Constants indentifying various devices on the network.
+enum class NetworkDevice {
+ // The computer that the cRIO talks to.
+ kAtom,
+ kCRIO,
+};
+// Returns the IP address to get to the specified machine.
+// The return value should be passed to free(3) if it is no longer needed.
+const char *GetIPAddress(NetworkDevice device);
+
+} // namespace configuration
+} // namespace aos
+
+#endif
diff --git a/aos/common/byteorder.h b/aos/common/byteorder.h
new file mode 100644
index 0000000..3444f98
--- /dev/null
+++ b/aos/common/byteorder.h
@@ -0,0 +1,132 @@
+#ifndef AOS_COMMON_BYTEORDER_H_
+#define AOS_COMMON_BYTEORDER_H_
+
+#ifndef __VXWORKS__
+#include <endian.h> // endian(3)
+#endif
+
+// Contains functions for converting between host and network byte order for
+// things other than 16/32 bit integers (those are provided by byteorder(3)).
+// Also gives a nice templated interface to these functions.
+
+namespace aos {
+
+#ifndef __VXWORKS__
+namespace {
+
+template<typename int_type, typename T, int_type (*function)(int_type)> static inline void copier(const void *in, void *out) {
+ static_assert(sizeof(T) == sizeof(int_type), "bad template args");
+ // Have confirmed by looking at the assembly code that this generates the same
+ // code as the (undefined by the c++ standard) way of using a union to do it.
+ // (which is pretty efficient)
+ int_type temp;
+ memcpy(&temp, in, sizeof(T));
+ temp = function(temp);
+ memcpy(out, &temp, sizeof(T));
+}
+template<typename int_type, typename T, int_type (*function)(int_type)> static inline T memcpier(T in) {
+ copier<int_type, T, function>(&in, &in);
+ return in;
+}
+
+// Can't make them static because they have to have external linkage to be used as a
+// template parameter.
+// Needed because be64toh etc are macros. (not that the manpage says anything...)
+// These are used instead of ntohs etc because gcc didn't inline those.
+inline uint64_t _be64toh(uint64_t in) { return be64toh(in); }
+inline uint64_t _htobe64(uint64_t in) { return htobe64(in); }
+inline uint32_t _be32toh(uint32_t in) { return be32toh(in); }
+inline uint32_t _htobe32(uint32_t in) { return htobe32(in); }
+inline uint16_t _be16toh(uint16_t in) { return be16toh(in); }
+inline uint16_t _htobe16(uint16_t in) { return htobe16(in); }
+
+template<int bytes, typename T> class do_ntoh {
+ public:
+ static inline T apply(T net);
+ static inline void copy(const char *in, T &net);
+};
+template<typename T> class do_ntoh<1, T> {
+ public:
+ static inline T apply(T net) { return net; }
+ static inline void copy(const char *in, T *host) { host[0] = in[0]; }
+};
+template<typename T> class do_ntoh<2, T> {
+ public:
+ static inline T apply(T net) { return memcpier<uint16_t, T, _be16toh>(net); }
+ static inline void copy(const char *in, T *host) { copier<uint16_t, T, _be16toh>(in, host); }
+};
+template<typename T> class do_ntoh<4, T> {
+ public:
+ static inline T apply(T net) { return memcpier<uint32_t, T, _be32toh>(net); }
+ static inline void copy(const char *in, T *host) { copier<uint32_t, T, _be32toh>(in, host); }
+};
+template<typename T> class do_ntoh<8, T> {
+ public:
+ static inline T apply(T net) { return memcpier<uint64_t, T, _be64toh>(net); }
+ static inline void copy(const char *in, T *host) { copier<uint64_t, T, _be64toh>(in, host); }
+};
+template<int bytes, typename T> class do_hton {
+ public:
+ static inline T apply(T host);
+ static inline void copy(const T *host, char *out);
+};
+template<typename T> class do_hton<1, T> {
+ public:
+ static inline T apply(T host) { return host; }
+ static inline void copy(const T *host, char *out) { out[0] = host[0]; }
+};
+template<typename T> class do_hton<2, T> {
+ public:
+ static inline T apply(T host) { return memcpier<uint16_t, T, _htobe16>(host); }
+ static inline void copy(const T *host, char *out) { copier<uint16_t, T, _htobe16>(host, out); }
+};
+template<typename T> class do_hton<4, T> {
+ public:
+ static inline T apply(T host) { return memcpier<uint32_t, T, _htobe32>(host); }
+ static inline void copy(const T *host, char *out) { copier<uint32_t, T, _htobe32>(host, out); }
+};
+template<typename T> class do_hton<8, T> {
+ public:
+ static inline T apply(T host) { return memcpier<uint64_t, T, _htobe64>(host); }
+ static inline void copy(const T *host, char *out) { copier<uint64_t, T, _htobe64>(host, out); }
+};
+
+} // namespace
+#endif // ifndef __VXWORKS__
+
+// Converts T from network to host byte order.
+template<typename T> static inline T ntoh(T net) {
+#ifndef __VXWORKS__
+ return do_ntoh<sizeof(net), T>::apply(net);
+#else
+ return net;
+#endif
+}
+// Converts T from host to network byte order.
+template<typename T> static inline T hton(T host) {
+#ifndef __VXWORKS__
+ return do_hton<sizeof(host), T>::apply(host);
+#else
+ return host;
+#endif
+}
+
+template<typename T> static inline void to_host(const char *input, T *host) {
+#ifndef __VXWORKS__
+ do_ntoh<sizeof(*host), T>::copy(input, host);
+#else
+ memcpy(host, input, sizeof(*host));
+#endif
+}
+template<typename T> static inline void to_network(const T *host, char *output) {
+#ifndef __VXWORKS__
+ do_hton<sizeof(*host), T>::copy(host, output);
+#else
+ memcpy(output, host, sizeof(*host));
+#endif
+}
+
+} // namespace aos
+
+#endif
+
diff --git a/aos/common/common.gyp b/aos/common/common.gyp
new file mode 100644
index 0000000..6dca969
--- /dev/null
+++ b/aos/common/common.gyp
@@ -0,0 +1,197 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'queue_test_queue',
+ 'type': 'static_library',
+ 'sources': [
+ '<(AOS)/common/test_queue.q',
+ ],
+ 'variables': {
+ 'header_path': 'aos/common',
+ },
+ 'dependencies': [
+ '<(AOS)/common/common.gyp:queues',
+ ],
+ 'includes': ['../build/queues.gypi'],
+ },
+ {
+ 'target_name': 'queue_testutils',
+ 'type': 'static_library',
+ 'sources': [
+ 'queue_testutils.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/atom_code/ipc_lib/ipc_lib.gyp:ipc_lib'
+ ],
+ },
+ {
+ 'target_name': 'time',
+ 'type': 'static_library',
+ 'sources': [
+ 'time.cc'
+ ],
+ 'dependencies': [
+ # TODO(aschuh): Fix this dependency loop by
+ # providing a logging interface.
+ # '<(AOS)/build/aos.gyp:logging',
+ '<(AOS)/build/aos.gyp:aos/ResourceList.h',
+ ],
+ },
+ {
+ 'target_name': 'common',
+ 'type': 'static_library',
+ 'sources': [
+ 'Configuration.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:logging',
+ ],
+ 'conditions': [
+ ['OS=="crio"', {
+ 'dependencies': [
+ '<(EXTERNALS):WPILib',
+ ]}],
+ ],
+ },
+ {
+ 'target_name': 'queues',
+ 'type': 'static_library',
+ 'sources': [
+ 'queue.cc',
+ ],
+ 'conditions': [
+ ['OS=="crio"', {
+ 'dependencies': [
+ '<(EXTERNALS):WPILib',
+ ],
+ },
+ {
+ 'dependencies': [
+ '<(AOS)/atom_code/ipc_lib/ipc_lib.gyp:ipc_lib',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/atom_code/ipc_lib/ipc_lib.gyp:ipc_lib',
+ ],
+ }]
+ ],
+ 'dependencies': [
+ '<(AOS)/common/common.gyp:common',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/common/common.gyp:common',
+ ],
+ },
+ {
+ 'target_name': 'control_loop_queues',
+ 'type': 'static_library',
+ 'sources': [ '<(AOS)/common/control_loop/control_loops.q' ],
+ 'variables': {
+ 'header_path': 'aos/common/control_loop',
+ },
+ 'dependencies': [
+ '<(AOS)/common/common.gyp:queues',
+ ],
+ 'includes': ['../build/queues.gypi'],
+ },
+ {
+ 'target_name': 'timing_so',
+ 'type': 'shared_library',
+ 'sources': [
+ 'control_loop/Timing.cpp'
+ ],
+ 'variables': {'no_rsync': 1},
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:aos_shared_lib',
+ ],
+ 'direct_dependent_settings': {
+ 'variables': {
+ 'jni_libs': [
+ 'timing_so',
+ ],
+ },
+ },
+ 'export_dependent_settings': [
+ '<(AOS)/build/aos.gyp:aos_shared_lib',
+ ],
+ },
+ {
+ 'target_name': 'timing',
+ 'type': 'static_library',
+ 'sources': [
+ 'control_loop/Timing.cpp'
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(AOS)/build/aos.gyp:logging',
+ ],
+ },
+ {
+ 'target_name': 'controls',
+ 'type': 'static_library',
+ 'sources': [],
+ 'dependencies': [
+ '<(AOS)/common/messages/messages.gyp:aos_queues',
+ '<(AOS)/build/aos.gyp:logging',
+ 'timing',
+ ],
+ },
+ {
+ 'target_name': 'queue_test',
+ 'type': 'executable',
+ 'sources': [
+ '<(AOS)/common/queue_test.cc',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ '<(AOS)/build/aos.gyp:libaos',
+ 'queue_testutils',
+ 'common',
+ 'queue_test_queue',
+ ],
+ },
+ {
+ 'target_name': 'type_traits_test',
+ 'type': '<(aos_target)',
+ 'sources': [
+ 'type_traits_test.cpp',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ {
+ 'target_name': 'time_test',
+ 'type': '<(aos_target)',
+ 'sources': [
+ 'time_test.cc',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ {
+ 'target_name': 'mutex_test',
+ 'type': '<(aos_target)',
+ 'sources': [
+ 'mutex_test.cpp',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ {
+ 'target_name': 'die_test',
+ 'type': 'executable',
+ 'sources': [
+ 'die_test.cc',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ },
+ ],
+}
diff --git a/aos/common/commonmath.h b/aos/common/commonmath.h
new file mode 100644
index 0000000..a77210f
--- /dev/null
+++ b/aos/common/commonmath.h
@@ -0,0 +1,18 @@
+#ifndef AOS_COMMON_MATH_H_
+#define AOS_COMMON_MATH_H_
+
+namespace aos {
+
+// Clips a value so that it is in [min, max]
+inline double Clip(double value, double min, double max) {
+ if (value > max) {
+ value = max;
+ } else if (value < min) {
+ value = min;
+ }
+ return value;
+}
+
+} // namespace aos
+
+#endif // AOS_COMMON_MATH_H_
diff --git a/aos/common/control_loop/ControlLoop-tmpl.h b/aos/common/control_loop/ControlLoop-tmpl.h
new file mode 100644
index 0000000..80d592a
--- /dev/null
+++ b/aos/common/control_loop/ControlLoop-tmpl.h
@@ -0,0 +1,122 @@
+#include <stddef.h>
+
+#include "aos/common/logging/logging.h"
+#include "aos/common/control_loop/Timing.h"
+#include "aos/common/messages/RobotState.q.h"
+
+namespace aos {
+namespace control_loops {
+
+// TODO(aschuh): Tests.
+
+template <class T, bool has_position>
+void ControlLoop<T, has_position>::ZeroOutputs() {
+ aos::ScopedMessagePtr<OutputType> output =
+ control_loop_->output.MakeMessage();
+ Zero(output.get());
+ output.Send();
+}
+
+template <class T, bool has_position>
+void ControlLoop<T, has_position>::Iterate() {
+ // Temporary storage for printing out inputs and outputs.
+ char state[1024];
+
+ // Fetch the latest control loop goal and position. If there is no new
+ // goal, we will just reuse the old one.
+ // If there is no goal, we haven't started up fully. It isn't worth
+ // the added complexity for each loop implementation to handle that case.
+ control_loop_->goal.FetchLatest();
+ // TODO(aschuh): Check the age here if we want the loop to stop on old
+ // goals.
+ const GoalType *goal = control_loop_->goal.get();
+ if (goal == NULL) {
+ LOG(ERROR, "No prior control loop goal.\n");
+ ZeroOutputs();
+ return;
+ }
+ goal->Print(state, sizeof(state));
+ LOG(DEBUG, "goal={%s}\n", state);
+
+ // Only pass in a position if we got one this cycle.
+ const PositionType *position = NULL;
+
+ // Only fetch the latest position if we have one.
+ if (has_position) {
+ // If the position is stale, this is really bad. Try fetching a position
+ // and check how fresh it is, and then take the appropriate action.
+ if (control_loop_->position.FetchLatest()) {
+ position = control_loop_->position.get();
+ } else {
+ if (control_loop_->position.get()) {
+ int msec_age = control_loop_->position.Age().ToMSec();
+ if (!control_loop_->position.IsNewerThanMS(kPositionTimeoutMs)) {
+ LOG(ERROR, "Stale position. %d ms > %d ms. Outputs disabled.\n",
+ msec_age, kPositionTimeoutMs);
+ ZeroOutputs();
+ return;
+ } else {
+ LOG(ERROR, "Stale position. %d ms\n", msec_age);
+ }
+ } else {
+ LOG(ERROR, "Never had a position.\n");
+ ZeroOutputs();
+ return;
+ }
+ }
+ position->Print(state, sizeof(state));
+ LOG(DEBUG, "position={%s}\n", state);
+ }
+
+ bool outputs_enabled = false;
+
+ // Check to see if we got a driver station packet recently.
+ if (aos::robot_state.FetchLatest()) {
+ outputs_enabled = true;
+ } else if (aos::robot_state.IsNewerThanMS(kDSPacketTimeoutMs)) {
+ outputs_enabled = true;
+ } else {
+ if (aos::robot_state.get()) {
+ int msec_age = aos::robot_state.Age().ToMSec();
+ LOG(ERROR, "Driver Station packet is too old (%d ms).\n", msec_age);
+ } else {
+ LOG(ERROR, "No Driver Station packet.\n");
+ }
+ }
+
+ // Run the iteration.
+ aos::ScopedMessagePtr<StatusType> status =
+ control_loop_->status.MakeMessage();
+ if (status.get() == NULL) {
+ return;
+ }
+
+ if (outputs_enabled) {
+ aos::ScopedMessagePtr<OutputType> output =
+ control_loop_->output.MakeMessage();
+ RunIteration(goal, position, output.get(), status.get());
+
+ output->Print(state, sizeof(state));
+ LOG(DEBUG, "output={%s}\n", state);
+ output.Send();
+ } else {
+ // The outputs are disabled, so pass NULL in for the output.
+ RunIteration(goal, position, NULL, status.get());
+ ZeroOutputs();
+ }
+
+ status->Print(state, sizeof(state));
+ LOG(DEBUG, "status={%s}\n", state);
+ status.Send();
+}
+
+template <class T, bool has_position>
+void ControlLoop<T, has_position>::Run() {
+ while (true) {
+ ::aos::time::PhasedLoop10MS(0);
+ Iterate();
+ }
+}
+
+} // namespace control_loops
+} // namespace aos
diff --git a/aos/common/control_loop/ControlLoop.h b/aos/common/control_loop/ControlLoop.h
new file mode 100644
index 0000000..b69cf01
--- /dev/null
+++ b/aos/common/control_loop/ControlLoop.h
@@ -0,0 +1,133 @@
+#ifndef AOS_CONTROL_LOOP_CONTROL_LOOP_H_
+#define AOS_CONTROL_LOOP_CONTROL_LOOP_H_
+
+#include <cstring>
+
+#include "aos/aos_core.h"
+#include "aos/common/control_loop/Timing.h"
+#include "aos/common/messages/RobotState.q.h"
+#include "aos/common/type_traits.h"
+
+namespace aos {
+namespace control_loops {
+
+// Interface to describe runnable jobs.
+class Runnable {
+ public:
+ virtual ~Runnable() {}
+ // Runs forever.
+ virtual void Run() = 0;
+ // Does one quick piece of work and return. Does _not_ block.
+ virtual void Iterate() = 0;
+};
+
+class SerializableControlLoop : public Runnable {
+ public:
+ // Returns the size of all the data to be sent when serialized.
+ virtual size_t SeralizedSize() = 0;
+ // Serialize the current data.
+ virtual void Serialize(char *buffer) const = 0;
+ // Serialize zeroed data in case the data is out of date.
+ virtual void SerializeZeroMessage(char *buffer) const = 0;
+ // Deserialize data into the control loop.
+ virtual void Deserialize(const char *buffer) = 0;
+ // Unique identifier for the control loop.
+ // Most likely the hash of the queue group.
+ virtual uint32_t UniqueID() = 0;
+};
+
+// Provides helper methods to assist in writing control loops.
+// This template expects to be constructed with a queue group as an argument
+// that has a goal, position, status, and output queue.
+// It will then call the RunIteration method every cycle that it has enough
+// valid data for the control loop to run.
+// If has_position is false, the control loop will always use NULL as the
+// position and not check the queue. This is used for "loops" that control
+// motors open loop.
+template <class T, bool has_position = true>
+class ControlLoop : public SerializableControlLoop {
+ public:
+ // Maximum age of position packets before the loop will be disabled due to
+ // invalid position data.
+ static const int kPositionTimeoutMs = 100;
+ // Maximum age of driver station packets before the loop will be disabled.
+ static const int kDSPacketTimeoutMs = 100;
+
+ ControlLoop(T *control_loop) : control_loop_(control_loop) {}
+
+ // Create some convenient typedefs to reference the Goal, Position, Status,
+ // and Output structures.
+ typedef typename std::remove_reference<
+ decltype(*(static_cast<T *>(NULL)->goal.MakeMessage().get()))>::type
+ GoalType;
+ typedef typename std::remove_reference<
+ decltype(*(static_cast<T *>(NULL)->position.MakeMessage().get()))>::type
+ PositionType;
+ typedef typename std::remove_reference<
+ decltype(*(static_cast<T *>(NULL)->status.MakeMessage().get()))>::type
+ StatusType;
+ typedef typename std::remove_reference<
+ decltype(*(static_cast<T *>(NULL)->output.MakeMessage().get()))>::type
+ OutputType;
+
+ // Constructs and sends a message on the output queue which will stop all the
+ // motors. Calls Zero to clear all the state.
+ void ZeroOutputs();
+
+ // Sets the output to zero.
+ // Over-ride if a value of zero is not "off" for this subsystem.
+ virtual void Zero(OutputType *output) { output->Zero(); }
+
+ // Runs the loop forever.
+ virtual void Run();
+
+ // Runs one cycle of the loop.
+ virtual void Iterate();
+
+ // Returns the name of the queue group.
+ const char *name() { return control_loop_->name(); }
+
+ // Methods to serialize all the data that should be sent over the network.
+ virtual size_t SeralizedSize() { return control_loop_->goal->Size(); }
+ virtual void Serialize(char *buffer) const {
+ control_loop_->goal->Serialize(buffer);
+ }
+ virtual void SerializeZeroMessage(char *buffer) const {
+ GoalType zero_goal;
+ zero_goal.Zero();
+ zero_goal.Serialize(buffer);
+ }
+
+ virtual void Deserialize(const char *buffer) {
+ ScopedMessagePtr<GoalType> new_msg = control_loop_->goal.MakeMessage();
+ new_msg->Deserialize(buffer);
+ new_msg.Send();
+ }
+
+ virtual uint32_t UniqueID() { return control_loop_->hash(); }
+
+ protected:
+ // Runs an iteration of the control loop.
+ // goal is the last goal that was sent. It might be any number of cycles old.
+ // position is the current position, or NULL if we didn't get a position this
+ // cycle.
+ // output is the values to be sent to the motors. This is NULL if the output
+ // is going to be ignored and set to 0.
+ // status is the status of the control loop.
+ // Both output and status should be filled in by the implementation.
+ virtual void RunIteration(const GoalType *goal,
+ const PositionType *position,
+ OutputType *output,
+ StatusType *status) = 0;
+
+ private:
+ // Pointer to the queue group
+ T *control_loop_;
+};
+
+} // namespace control_loops
+} // namespace aos
+
+#include "aos/common/control_loop/ControlLoop-tmpl.h" // IWYU pragma: export
+
+#endif
diff --git a/aos/common/control_loop/Timing.cpp b/aos/common/control_loop/Timing.cpp
new file mode 100644
index 0000000..63fda44
--- /dev/null
+++ b/aos/common/control_loop/Timing.cpp
@@ -0,0 +1,19 @@
+#include "aos/common/logging/logging.h"
+#include "aos/common/control_loop/Timing.h"
+
+#include "aos/common/time.h"
+
+namespace aos {
+namespace time {
+
+void PhasedLoopXMS(int ms, int offset) {
+ // TODO(brians): Rewrite this cleaner.
+ // TODO(brians): Tests!
+ int64_t period_nsec = Time::InMS(ms).nsec();
+ SleepUntil(Time::InNS((Time::Now().ToNSec() / period_nsec +
+ static_cast<int64_t>(1)) * period_nsec +
+ Time::InUS(offset).ToNSec()));
+}
+
+} // namespace timing
+} // namespace aos
diff --git a/aos/common/control_loop/Timing.h b/aos/common/control_loop/Timing.h
new file mode 100644
index 0000000..139376d
--- /dev/null
+++ b/aos/common/control_loop/Timing.h
@@ -0,0 +1,19 @@
+#ifndef __AOS_TIMEOUT_H_
+#define __AOS_TIMEOUT_H_
+
+#include <time.h>
+#include <string>
+
+namespace aos {
+namespace time {
+
+// Will not be accurate if ms isn't a factor of 1000.
+// offset is in us.
+void PhasedLoopXMS(int ms, int offset);
+// offset is in us.
+inline void PhasedLoop10MS(int offset) { PhasedLoopXMS(10, offset); }
+
+} // namespace time
+} // namespace aos
+
+#endif
diff --git a/aos/common/control_loop/control_loops.q b/aos/common/control_loop/control_loops.q
new file mode 100644
index 0000000..5ba30ec
--- /dev/null
+++ b/aos/common/control_loop/control_loops.q
@@ -0,0 +1,38 @@
+package aos.control_loops;
+
+interface IsDone {
+ bool done;
+};
+
+interface ControlLoop {
+ queue goal;
+ queue position;
+ queue output;
+ queue IsDone status;
+};
+
+message Goal {
+ double goal;
+};
+
+message Position {
+ double position;
+};
+
+message Output {
+ double pwm;
+};
+
+message Status {
+ bool done;
+};
+
+// Single Input Single Output control loop.
+queue_group SISO {
+ implements ControlLoop;
+
+ queue Goal goal;
+ queue Position position;
+ queue Output output;
+ queue Status status;
+};
diff --git a/aos/common/debugging-tips.txt b/aos/common/debugging-tips.txt
new file mode 100644
index 0000000..5d52af2
--- /dev/null
+++ b/aos/common/debugging-tips.txt
@@ -0,0 +1,48 @@
+[General]
+Check the logs! Very few things will fail without putting something in the logs.
+ If they do, that is a bug unless our code is never getting run (there are
+ innumerable ways that could happen, but it generally doesn't).
+ To check the logs, run `LogDisplayer` if `BinaryLogReader` has been started or
+ just run `LogStreamer` if you want to do simple testing without writing logs
+ to a file. See `LogDisplayer --help` for options.
+All of the binaries get put in the same place. That is
+ src/out_atom/Default/outputs on the build machine and
+ /home/driver/robot_code/bin on the fitpc.
+
+[Startup]
+Low level startup errors often end up in /aos_fatal_error.* on the cRIO and
+ /tmp/aos_fatal_error.* under linux. Also helpful are the /tmp/starter*_std*
+ files (if the standard start scripts are being used) and
+ aos/crio/bin/netconsole.sh for reading cRIO stdout and stderr.
+ If lots of the /tmp/starter_*std* files (with different numbers) are being
+ created, that means that starter_exe is dying constantly.
+
+[Anything Not Running]
+Check starter_exe's log messages. They might mention that it is constantly dying
+ on startup and being restarted.
+
+[Control Loop(s) Not Working]
+Are robot_state messages going out? An aos::JoystickInput (often JoystickReader)
+ should be sending them.
+Is it being fed goal messages?
+Is it getting position messages?
+Is something looking at the output and doing something useful with it?
+
+[No Driver Station Packets]
+Check to make sure that JSR (a cRIO-side task) is saying that it's sending
+ messages. Also check JoystickReader (or whatever inherits from
+ aos::JoystickInput) is running and see if it's receiving anything.
+
+[Attaching a Debugger]
+In order to make attaching a debugger very useful, you have to compile the code
+ with debugging symbols. The way to do that is to modify the appropriate
+ build.sh to pass "yes" instead of "no" as an argument to the aos build.sh. You
+ have to modify a .gyp file (touching it is sufficient) to get it to use the
+ new build flag.
+Attaching GDB to an existing robot code process works like normal (you have to
+ root first because that's what all of the code currently runs as).
+If a process is dying repeatedly, the easiest way to debug it is to kill
+ starter_loop.sh and (it has to be after that) starter_exe. After doing that,
+ NOTHING will get restarted (including the normal restart after changing a
+ binary) so that you can start a process under GDB like usual (shouldn't need
+ anything special if done as root).
diff --git a/aos/common/die.cc b/aos/common/die.cc
new file mode 100644
index 0000000..195df45
--- /dev/null
+++ b/aos/common/die.cc
@@ -0,0 +1,77 @@
+#include "aos/common/die.h"
+
+#include <stdlib.h>
+#include <stdio.h>
+#include <errno.h>
+#include <sys/types.h>
+#include <unistd.h>
+#include <string.h>
+#ifdef __VXWORKS__
+#include <taskLib.h>
+// Have to re-declare it with __attribute__((noreturn)).
+extern "C" void abort() __attribute__((noreturn));
+#endif
+
+#include <string>
+
+#include "aos/aos_stdint.h"
+
+namespace aos {
+
+void Die(const char *format, ...) {
+ va_list args;
+ va_start(args, format);
+ VDie(format, args);
+}
+
+namespace {
+// Calculates the filename to dump the message into.
+const std::string GetFilename() {
+#ifdef __VXWORKS__
+ const char *name = taskName(0); // get the name of this task
+ if (name == NULL) name = "<unknown>";
+ const std::string first_part = "/aos_fatal_error.";
+ return first_part + std::string(name);
+#else
+ char *filename;
+ if (asprintf(&filename, "/tmp/aos_fatal_error.%jd",
+ static_cast<intmax_t>(getpid())) > 0) {
+ std::string r(filename);
+ free(filename);
+ return r;
+ } else {
+ fprintf(stderr, "aos fatal: asprintf(%p, \"thingie with %%jd\", %jd)"
+ " failed with %d (%s)\n", &filename,
+ static_cast<intmax_t>(getpid()), errno, strerror(errno));
+ return std::string();
+ }
+#endif
+}
+} // namespace
+void VDie(const char *format, va_list args_in) {
+ va_list args;
+
+ fputs("aos fatal: ERROR!! details following\n", stderr);
+ va_copy(args, args_in);
+ vfprintf(stderr, format, args);
+ va_end(args);
+ fputs("aos fatal: ERROR!! see stderr for details\n", stdout);
+
+ const std::string filename = GetFilename();
+ if (!filename.empty()) {
+ FILE *error_file = fopen(filename.c_str(), "w");
+ if (error_file != NULL) {
+ va_copy(args, args_in);
+ vfprintf(error_file, format, args);
+ va_end(args);
+ fclose(error_file);
+ } else {
+ fprintf(stderr, "aos fatal: fopen('%s', \"w\") failed with %d (%s)\n",
+ filename.c_str(), errno, strerror(errno));
+ }
+ }
+
+ abort();
+}
+
+} // namespace aos
diff --git a/aos/common/die.h b/aos/common/die.h
new file mode 100644
index 0000000..28519a8
--- /dev/null
+++ b/aos/common/die.h
@@ -0,0 +1,20 @@
+#ifndef AOS_COMMON_DIE_H_
+#define AOS_COMMON_DIE_H_
+
+#include <stdarg.h>
+
+namespace aos {
+
+// Terminates the task/process and logs a message (without using the logging
+// framework). Designed for use in code that can't use the logging framework
+// (code that can should LOG(FATAL), which calls this).
+void Die(const char *format, ...)
+ __attribute__((noreturn))
+ __attribute__((format(gnu_printf, 1, 2)));
+void VDie(const char *format, va_list args)
+ __attribute__((noreturn))
+ __attribute__((format(gnu_printf, 1, 0)));
+
+} // namespace aos
+
+#endif // AOS_COMMON_DIE_H_
diff --git a/aos/common/die_test.cc b/aos/common/die_test.cc
new file mode 100644
index 0000000..687543c
--- /dev/null
+++ b/aos/common/die_test.cc
@@ -0,0 +1,14 @@
+#include "aos/common/die.h"
+
+#include "gtest/gtest.h"
+
+namespace aos {
+namespace testing {
+
+TEST(DieDeathTest, Works) {
+ EXPECT_EXIT(Die("str=%s num=%d\n", "hi", 5),
+ ::testing::KilledBySignal(SIGABRT), ".*str=hi num=5\n");
+}
+
+} // namespace testing
+} // namespace aos
diff --git a/aos/common/input/SensorInput-tmpl.h b/aos/common/input/SensorInput-tmpl.h
new file mode 100644
index 0000000..e92a923
--- /dev/null
+++ b/aos/common/input/SensorInput-tmpl.h
@@ -0,0 +1,41 @@
+#include "aos/common/input/SensorInput.h"
+#ifndef __VXWORKS__
+#include "aos/common/network/ReceiveSocket.h"
+#include "aos/common/Configuration.h"
+#endif
+
+namespace aos {
+
+#ifdef __VXWORKS__
+template<class Values> SEM_ID SensorInput<Values>::lock_ = semBCreate(SEM_Q_PRIORITY, SEM_FULL);
+template<class Values> std::vector<SensorInput<Values> *> SensorInput<Values>::running_;
+#endif
+template<class Values> void SensorInput<Values>::Run() {
+#ifndef __VXWORKS__
+ ReceiveSocket sock(NetworkPort::kSensors);
+ Values values;
+ while (true) {
+ if (sock.Recv(&values, sizeof(values)) == -1) {
+ LOG(WARNING, "socket receive failed\n");
+ continue;
+ }
+ RunIteration(values);
+ }
+#else
+ semTake(lock_, WAIT_FOREVER);
+ running_.push_back(this);
+ semGive(lock_);
+#endif
+}
+
+#ifdef __VXWORKS__
+template<class Values> void SensorInput<Values>::RunIterationAll(Values &vals) {
+ semTake(lock_, WAIT_FOREVER);
+ for (auto it = running_.begin(); it != running_.end(); ++it) {
+ (*it)->RunIteration(vals);
+ }
+ semGive(lock_);
+}
+#endif
+
+} // namespace aos
diff --git a/aos/common/input/SensorInput.h b/aos/common/input/SensorInput.h
new file mode 100644
index 0000000..7f8eaa7
--- /dev/null
+++ b/aos/common/input/SensorInput.h
@@ -0,0 +1,36 @@
+#ifndef AOS_INPUT_SENSOR_INPUT_H_
+#define AOS_INPUT_SENSOR_INPUT_H_
+
+#include "aos/aos_core.h"
+#ifdef __VXWORKS__
+#include <vector>
+#include <semLib.h>
+#endif
+
+namespace aos {
+
+// Class for implementing code that takes information from a sensor struct and
+// places it into queues. Subclasses should be compiled for both the atom and
+// the crio to support crio control loops.
+template<class Values> class SensorInput {
+ protected:
+ virtual void RunIteration(Values &values) = 0;
+ public:
+ // Enters an infinite loop that reads values and calls RunIteration.
+ void Run();
+
+#ifdef __VXWORKS__
+ // Calls RunIteration on all instances with values.
+ static void RunIterationAll(Values &values);
+ private:
+ static SEM_ID lock_;
+ static std::vector<SensorInput *> running_;
+#endif
+};
+
+} // namespace aos
+
+#include "SensorInput-tmpl.h"
+
+#endif
+
diff --git a/aos/common/inttypes.h b/aos/common/inttypes.h
new file mode 100644
index 0000000..e10a33b
--- /dev/null
+++ b/aos/common/inttypes.h
@@ -0,0 +1,19 @@
+#ifndef AOS_COMMON_INTTYPES_H_
+#define AOS_COMMON_INTTYPES_H_
+
+// This file is here because the vxworks headers do not have an inttypes.h file
+// and being able to print out fixed size types is very useful. Any fixed size
+// formats that we need on the cRIO should get added here.
+
+#ifndef __VXWORKS__
+#include <inttypes.h>
+#else
+// It warns about just "d", but not this, which is kind of weird because
+// sizeof(int) == sizeof(long) == sizeof(int32_t) == 4, but oh well.
+#define PRId32 "ld"
+#define PRIx32 "lx"
+#define PRId64 "lld"
+#define PRIu16 "u"
+#endif
+
+#endif // AOS_COMMON_INTTYPES_H_
diff --git a/aos/common/logging/logging.h b/aos/common/logging/logging.h
new file mode 100644
index 0000000..e3ff839
--- /dev/null
+++ b/aos/common/logging/logging.h
@@ -0,0 +1,102 @@
+#ifndef AOS_COMMON_LOGGING_LOGGING_H_
+// must be kept in sync with crio/logging/crio_logging.h and atom_code/logging/atom_logging.h
+#define AOS_COMMON_LOGGING_LOGGING_H_
+
+#include <stdint.h>
+#include <sys/types.h>
+#include <unistd.h>
+#include <string.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+typedef uint8_t log_level;
+#define DECL_LEVELS \
+DECL_LEVEL(DEBUG, 0); /* stuff that gets printed out every cycle */ \
+DECL_LEVEL(INFO, 1); /* things like PosEdge/NegEdge */ \
+/* things that might still work if they happen occasionally but should be watched */ \
+DECL_LEVEL(WARNING, 2); \
+/*-1 so that vxworks macro of same name will have same effect if used*/ \
+DECL_LEVEL(ERROR, -1); /* errors */ \
+DECL_LEVEL(FATAL, 4); /* serious errors. the logging code will terminate the process/task */ \
+DECL_LEVEL(LOG_UNKNOWN, 5); /* unknown logging level */
+#define DECL_LEVEL(name, value) extern const log_level name;
+#undef ERROR
+DECL_LEVELS
+#undef DECL_LEVEL
+
+#define STRINGIFY(x) TO_STRING(x)
+#define TO_STRING(x) #x
+
+//not static const size_t for c code
+#define LOG_MESSAGE_LEN 300
+
+// Allows format to not be a string constant.
+#define LOG_DYNAMIC(level, format, args...) do{ \
+ static char log_buf[LOG_MESSAGE_LEN]; \
+ int ret = snprintf(log_buf, sizeof(log_buf), format, ##args); \
+ if(ret < 0 || (uintmax_t)ret >= LOG_MESSAGE_LEN){ \
+ LOG(WARNING, "next message was too long so not subbing in args\n"); \
+ LOG(level, "%s", format); \
+ }else{ \
+ LOG(level, "%s", log_buf); \
+ } \
+}while(0)
+
+// The struct that the crio-side code uses for making logging calls.
+// Packed so it's the same on the atom and the crio.
+typedef struct {
+ // pid_t here at the front like in log_message
+ pid_t identifier; // must ALWAYS be -1 to identify that this is a crio log message
+ log_level level;
+ // still has to fit in LOG_MESSAGE_LEN on the atom side
+ char message[LOG_MESSAGE_LEN - 50];
+ double time;
+ uint8_t sequence;
+} __attribute__((packed)) log_crio_message;
+
+#ifdef __cplusplus
+// Just sticks the message into the shared memory queue.
+int log_crio_message_send(log_crio_message &to_send);
+// Returns left > right. LOG_UNKNOWN is most important.
+static inline bool log_gt_important(log_level left, log_level right) {
+ log_level l = left, r = right;
+ if (l == ERROR) l = 3;
+ if (r == ERROR) r = 3;
+ return left > right;
+}
+#endif
+
+// Returns a string representing level or "unknown".
+static inline const char *log_str(log_level level) {
+ // c doesn't really have const variables so they don't work in case statements
+ if (level == DEBUG) return "DEBUG";
+ if (level == INFO) return "INFO";
+ if (level == WARNING) return "WARNING";
+ if (level == ERROR) return "ERROR";
+ if (level == FATAL) return "FATAL";
+ return "unknown";
+}
+// Returns the log level represented by str or LOG_UNKNOWN.
+static inline log_level str_log(const char *str) {
+ if (!strcmp(str, "DEBUG")) return DEBUG;
+ if (!strcmp(str, "INFO")) return INFO;
+ if (!strcmp(str, "WARNING")) return WARNING;
+ if (!strcmp(str, "ERROR")) return ERROR;
+ if (!strcmp(str, "FATAL")) return FATAL;
+ return LOG_UNKNOWN;
+}
+
+#ifdef __cplusplus
+}
+#endif
+
+#ifdef __unix
+#include "aos/atom_code/logging/atom_logging.h" // IWYU pragma: export
+#else
+#include "aos/crio/logging/crio_logging.h" // IWYU pragma: export
+#endif
+
+#endif
+
diff --git a/aos/common/macros.h b/aos/common/macros.h
new file mode 100644
index 0000000..88fc52e
--- /dev/null
+++ b/aos/common/macros.h
@@ -0,0 +1,25 @@
+#ifndef _AOS_COMMON_MACROS_H_
+#define _AOS_COMMON_MACROS_H_
+
+// This file has some common macros etc.
+
+// A macro to disallow the copy constructor and operator= functions
+// This should be used in the private: declarations for a class
+#define DISALLOW_COPY_AND_ASSIGN(TypeName) \
+ TypeName(const TypeName&); \
+ void operator=(const TypeName&)
+// A macro to wrap arguments to macros that contain commas.
+// Useful for DISALLOW_COPY_AND_ASSIGNing templated types with multiple template
+// arguments.
+#define MACRO_ARG(...) __VA_ARGS__
+// Double-wraps macro arguments.
+// Necessary to use commas in gtest predicate arguments.
+#define MACRO_DARG(...) (__VA_ARGS__)
+
+#ifdef __GNUC__
+#define UNUSED_VARIABLE __attribute__ ((unused))
+#else
+#define UNUSED_VARIABLE
+#endif
+
+#endif // _AOS_COMMON_MACROS_H_
diff --git a/aos/common/messages/QueueHolder.h b/aos/common/messages/QueueHolder.h
new file mode 100644
index 0000000..6cf2835
--- /dev/null
+++ b/aos/common/messages/QueueHolder.h
@@ -0,0 +1,173 @@
+#ifndef __AOS_MESSAGES_QUEUE_HOLDER_H_
+#define __AOS_MESSAGES_QUEUE_HOLDER_H_
+
+#include <stddef.h>
+
+#include <algorithm>
+
+#include "aos/aos_core.h"
+#include "aos/common/control_loop/Timing.h"
+#include "aos/common/byteorder.h"
+#include "aos/common/time.h"
+#include "aos/common/type_traits.h"
+
+namespace aos {
+
+// Specializations of TypeOperator and QueueBuilder that are actually
+// implemented are created in the generated code for all message value types.
+// These specializations have the same functions declared in the actual types.
+
+// Defines a way for types to be manipulated.
+template<typename T> class TypeOperator {
+ public:
+ // Sets all fields to their default constructor.
+ static void Zero(T &t_);
+ // Returns the size of buffer NToH and HToN use.
+ static size_t Size();
+ // Converts everything from network to host byte order.
+ // input must have Size() bytes available in it.
+ static void NToH(char *input, T &t_);
+ // Converts everything from host to network byte order and puts it into output.
+ // output must have Size() bytes available in it.
+ static void HToN(const T &t_, char *output);
+ // Creates a string with the names and values of all the fields.
+ // The return value might will be to a static buffer.
+ static const char *Print(const T &t_);
+};
+
+template<typename T> class QueueHolder;
+
+// An easy way to set values for queue messages.
+// Each specialization has chainable setter functions for building a message
+// of type T to put into a queue (like QueueBuilder<T> &field(int value);).
+template<class T> class QueueBuilder {
+ public:
+ QueueBuilder(QueueHolder<T> &holder);
+ bool Send();
+};
+
+// Internal class to make implementing identical behavior with structs that go
+// into queues easier. Also a central location for the documentation.
+//
+// When compiled for the cRIO, everything except Clear does nothing (and Get
+// turns into just a Clear) which means that the internal T instance is the only one.
+// Also, the internal instance becomes static.
+//
+// To look at the current message, you Get a copy and then View the result.
+// To make changes, you modify the message that you can View (after possibly
+// Clearing it) and then you Send it. You can also just Clear the message, put
+// data into it, and then Send it. A way to modify the local message is using
+// the Builder function.
+// Note that there is no way to avoid potentially overwriting other changes between
+// when you Get one and when you Send it (mainly applicable to 1-length queues).
+//
+// T must be POD and have a "timespec set_time;" field.
+//
+// This first class doesn't have the builder; QueueHolder does.
+#define aos_check_rv __attribute__((warn_unused_result))
+template<typename T> class QueueHolderNoBuilder {
+#ifndef __VXWORKS__
+ aos_queue *const queue_;
+ static_assert(shm_ok<T>::value, "T must be able to"
+ " go through shared memory and memcpy");
+ T t_;
+#else
+ static T t_;
+#endif
+ public:
+#ifndef __VXWORKS__
+ explicit QueueHolderNoBuilder(aos_queue *queue) : queue_(queue) {}
+#else
+ QueueHolderNoBuilder() {}
+#endif
+ // Gets the current value and stores it in View().
+ // check_time is whether or not to check to see if the last time a value was Sent
+ // was too long ago (returns false if it was)
+ // Returns true if View() is now the current value.
+ // IMPORTANT: If this function returns false, the contents of View() are
+ // either the same as they were before or (if check_time is true) the current
+ // message. That is why it creates compile-time warnings if the return value
+ // is not checked.
+ bool Get(bool check_time) aos_check_rv;
+ // Looks at the current value. Starts out undefined.
+ // If the last Get call returned false, then this the contents of the
+ // return value are undefined.
+#ifdef __VXWORKS__
+ static
+#endif
+ inline T &View() { return t_; }
+ // Clears (calls the default constructor of) all the fields of the current
+ // Goal.
+ void Clear() { TypeOperator<T>::Zero(t_); }
+ // Sends the current value. Does not affect the current value.
+ // Returns whether or not the Send succeeded.
+ bool Send();
+ // Returns a string containing the values of all the fields in the current
+ // value.
+ // The return value is valid until Print is called again. The class owns the
+ // memory.
+ const char *Print() const { return TypeOperator<T>::Print(t_); }
+};
+
+template<typename T>
+bool QueueHolderNoBuilder<T>::Get(bool check_time) {
+#ifdef __VXWORKS__
+ (void)check_time;
+ return true;
+#else
+ const T *msg = static_cast<const T *>(aos_queue_read_msg(queue_,
+ PEEK | NON_BLOCK));
+ if (msg == NULL) {
+ return false;
+ }
+ static_assert(sizeof(t_) == sizeof(*msg), "something is wrong here");
+ memcpy(&t_, msg, sizeof(t_));
+ aos_queue_free_msg(queue_, msg);
+ if (check_time && !((time::Time::Now() - time::Time(t_.set_time)) > time::Time::InMS(45))) {
+ LOG(WARNING, "too long since last Set msg={%s}\n", Print());
+ return false;
+ } else {
+ return true;
+ }
+#endif
+}
+template<typename T>
+bool QueueHolderNoBuilder<T>::Send() {
+#ifndef __VXWORKS__
+ T *msg = static_cast<T *>(aos_queue_get_msg(queue_));
+ if (msg == NULL) {
+ return false;
+ }
+ static_assert(sizeof(*msg) == sizeof(t_), "something is wrong here");
+ memcpy(msg, &t_, sizeof(t_));
+ msg->set_time = ::aos::time::Time::Now().ToTimespec();
+
+ return aos_queue_write_msg_free(queue_, msg, OVERRIDE) == 0;
+#else
+ return true;
+#endif
+}
+#ifdef __VXWORKS__
+template<typename T> T QueueHolderNoBuilder<T>::t_;
+#endif
+template<typename T> class QueueHolder : public QueueHolderNoBuilder<T> {
+ QueueBuilder<T> builder_;
+ public:
+#ifndef __VXWORKS__
+ explicit QueueHolder(aos_queue *queue) : QueueHolderNoBuilder<T>(queue),
+ builder_(*this) {}
+#else
+ QueueHolder() : builder_(*this) {}
+#endif
+ // Clears the current Goal and returns an object that allows setting various
+ // fields with chained method calls and then calling Send() on it.
+ QueueBuilder<T> &Builder() {
+ QueueHolderNoBuilder<T>::Clear();
+ return builder_;
+ }
+};
+
+} // namespace aos
+
+#endif
+
diff --git a/aos/common/messages/QueueHolder.swg b/aos/common/messages/QueueHolder.swg
new file mode 100644
index 0000000..816e297
--- /dev/null
+++ b/aos/common/messages/QueueHolder.swg
@@ -0,0 +1,9 @@
+namespace aos {
+
+template<class T> class QueueBuilder {
+ public:
+ bool Send();
+};
+
+} // namespace aos
+
diff --git a/aos/common/messages/RobotState.q b/aos/common/messages/RobotState.q
new file mode 100644
index 0000000..32baa05
--- /dev/null
+++ b/aos/common/messages/RobotState.q
@@ -0,0 +1,14 @@
+package aos;
+
+message RobotState {
+ bool enabled;
+ bool autonomous;
+ uint16_t team_id;
+};
+
+// The robot_state Queue is checked by all control loops to make sure that the
+// joystick code hasn't died.
+// It also provides information about whether or not the robot is in autonomous
+// mode and what the team_id is.
+
+queue RobotState robot_state;
diff --git a/aos/common/messages/messages.gyp b/aos/common/messages/messages.gyp
new file mode 100644
index 0000000..94508c4
--- /dev/null
+++ b/aos/common/messages/messages.gyp
@@ -0,0 +1,45 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'aos_queues',
+ 'type': 'static_library',
+ 'sources': [
+ 'RobotState.q',
+ ],
+ 'variables': {
+ 'header_path': 'aos/common/messages',
+ },
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:aos_internal_nolib',
+ '<(AOS)/common/common.gyp:queues',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/build/aos.gyp:aos_internal_nolib',
+ '<(AOS)/common/common.gyp:queues',
+ ],
+ 'includes': ['../../build/queues.gypi'],
+ },
+ {
+ 'target_name': 'queues_so',
+ 'type': 'shared_library',
+ 'sources': [
+ 'RobotState.q',
+ ],
+ 'variables': {
+ 'header_path': 'aos/common/messages',
+ },
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:aos_internal_nolib',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/build/aos.gyp:aos_internal_nolib',
+ ],
+ 'direct_dependent_settings': {
+ 'variables': {
+ 'jni_libs': ['queues_so'],
+ },
+ },
+ 'includes': ['../../build/queues.gypi'],
+ },
+ ],
+}
diff --git a/aos/common/mutex.h b/aos/common/mutex.h
new file mode 100644
index 0000000..c1d6f95
--- /dev/null
+++ b/aos/common/mutex.h
@@ -0,0 +1,70 @@
+#ifndef AOS_COMMON_MUTEX_H_
+#define AOS_COMMON_MUTEX_H_
+
+#ifdef __VXWORKS__
+#include <semLib.h>
+#endif
+
+#include "aos/aos_core.h"
+#include "aos/common/macros.h"
+#include "aos/common/type_traits.h"
+
+namespace aos {
+
+// An abstraction of a mutex that has implementations both for the
+// atom and for the cRIO.
+// If there are multiple tasks or processes contending for the mutex,
+// higher priority ones will succeed in locking first,
+// and tasks of equal priorities have the same chance of getting the lock.
+// There is no priority inversion protection.
+class Mutex {
+ public:
+ // Creates an unlocked mutex.
+ Mutex();
+#ifdef __VXWORKS__
+ // Will not make sure that it is either locked or unlocked.
+ ~Mutex();
+#endif
+ // Locks the mutex. If it fails, it calls LOG(FATAL).
+ void Lock();
+ // Unlocks the mutex. Fails like Lock.
+ // Multiple unlocking might be considered failure.
+ void Unlock();
+ // Locks the mutex unless it is already locked.
+ // Returns whether it succeeded or not.
+ // Doesn't wait for the mutex to be unlocked if it is locked.
+ bool TryLock();
+
+ private:
+#ifdef __VXWORKS__
+ typedef SEM_ID ImplementationType;
+#else
+ typedef mutex ImplementationType;
+#endif
+ ImplementationType impl_;
+#ifdef __VXWORKS__
+ DISALLOW_COPY_AND_ASSIGN(Mutex);
+#endif
+};
+
+// A class that locks a Mutex when constructed and unlocks it when destructed.
+// Designed to be used as a local variable so that
+// the mutex will be unlocked when the scope is exited.
+// Should it fail for some reason, it dies with LOG(FATAL).
+class MutexLocker {
+ public:
+ explicit MutexLocker(Mutex *mutex) : mutex_(mutex) {
+ mutex_->Lock();
+ }
+ ~MutexLocker() {
+ mutex_->Unlock();
+ }
+
+ private:
+ Mutex *mutex_;
+ DISALLOW_COPY_AND_ASSIGN(MutexLocker);
+};
+
+} // namespace aos
+
+#endif // AOS_COMMON_MUTEX_H_
diff --git a/aos/common/mutex_test.cpp b/aos/common/mutex_test.cpp
new file mode 100644
index 0000000..a5d5e86
--- /dev/null
+++ b/aos/common/mutex_test.cpp
@@ -0,0 +1,55 @@
+#include "aos/common/mutex.h"
+
+#include "gtest/gtest.h"
+
+namespace aos {
+namespace testing {
+
+class MutexTest : public ::testing::Test {
+ public:
+ Mutex test_mutex;
+};
+
+typedef MutexTest MutexDeathTest;
+
+TEST_F(MutexTest, TryLock) {
+ EXPECT_TRUE(test_mutex.TryLock());
+ EXPECT_FALSE(test_mutex.TryLock());
+}
+
+TEST_F(MutexTest, Lock) {
+ test_mutex.Lock();
+ EXPECT_FALSE(test_mutex.TryLock());
+}
+
+TEST_F(MutexTest, Unlock) {
+ test_mutex.Lock();
+ EXPECT_FALSE(test_mutex.TryLock());
+ test_mutex.Unlock();
+ EXPECT_TRUE(test_mutex.TryLock());
+}
+
+#ifndef __VXWORKS__
+// Sees what happens with multiple unlocks.
+TEST_F(MutexDeathTest, RepeatUnlock) {
+ test_mutex.Lock();
+ test_mutex.Unlock();
+ EXPECT_DEATH(test_mutex.Unlock(), ".*multiple unlock.*");
+}
+
+// Sees what happens if you unlock without ever locking (or unlocking) it.
+TEST_F(MutexDeathTest, NeverLock) {
+ EXPECT_DEATH(test_mutex.Unlock(), ".*multiple unlock.*");
+}
+#endif
+
+TEST_F(MutexTest, MutexLocker) {
+ {
+ aos::MutexLocker locker(&test_mutex);
+ EXPECT_FALSE(test_mutex.TryLock());
+ }
+ EXPECT_TRUE(test_mutex.TryLock());
+}
+
+} // namespace testing
+} // namespace aos
diff --git a/aos/common/network/ReceiveSocket.cpp b/aos/common/network/ReceiveSocket.cpp
new file mode 100644
index 0000000..671f966
--- /dev/null
+++ b/aos/common/network/ReceiveSocket.cpp
@@ -0,0 +1,32 @@
+#include "ReceiveSocket.h"
+#include <string.h>
+#include <math.h>
+#include <errno.h>
+#include <stdint.h>
+#include <stddef.h>
+
+#include "aos/common/network/SocketLibraries.h"
+#include "aos/aos_core.h"
+
+namespace aos {
+
+static const char *localhost = "0.0.0.0";
+
+int ReceiveSocket::Connect(NetworkPort port) {
+ Reset();
+ const int ret = Socket::Connect(port, localhost);
+ if (ret != 0) {
+ return ret;
+ }
+
+ if (bind(socket_, &addr_.addr,
+ sizeof(addr_)) == -1) {
+ LOG(ERROR, "failed to bind to address '%s' because of %d: %s\n", localhost,
+ errno, strerror(errno));
+ return last_ret_ = -1;
+ }
+ return last_ret_ = 0;
+}
+
+} // namespace aos
+
diff --git a/aos/common/network/ReceiveSocket.h b/aos/common/network/ReceiveSocket.h
new file mode 100644
index 0000000..bd834c9
--- /dev/null
+++ b/aos/common/network/ReceiveSocket.h
@@ -0,0 +1,19 @@
+#ifndef AOS_NETWORK_RECEIVE_SOCKET_H_
+#define AOS_NETWORK_RECEIVE_SOCKET_H_
+
+#include "Socket.h"
+
+namespace aos {
+
+class ReceiveSocket : public Socket {
+ public:
+ inline ReceiveSocket(NetworkPort port) { Connect(port); }
+ int Connect(NetworkPort port);
+
+ inline int Recv(void *buf, int length) { return Socket::Recv(buf, length); }
+ inline int Recv(void *buf, int length, long usec) { return Socket::Recv(buf, length, usec); }
+};
+
+} // namespace aos
+
+#endif
diff --git a/aos/common/network/SendSocket.cpp b/aos/common/network/SendSocket.cpp
new file mode 100644
index 0000000..89665dc
--- /dev/null
+++ b/aos/common/network/SendSocket.cpp
@@ -0,0 +1,42 @@
+#include "aos/common/network/SendSocket.h"
+
+#include <string.h>
+#include <errno.h>
+#include <stdint.h>
+#include <stddef.h>
+#include <math.h>
+
+#include "aos/aos_core.h"
+#include "aos/common/network/SocketLibraries.h"
+
+namespace aos {
+
+int SendSocket::Connect(NetworkPort port, const char *robot_ip, int type) {
+ Reset();
+ const int ret = Socket::Connect(port, robot_ip, type);
+ if (ret != 0) {
+ return ret;
+ }
+
+ if (connect(socket_, &addr_.addr,
+ sizeof(addr_)) < 0) {
+ LOG(ERROR, "couldn't connect to ip '%s' because of %d: %s\n", robot_ip,
+ errno, strerror(errno));
+ last_ret_ = 1;
+ }
+
+ hold_msg_len_ = 0;
+ return last_ret_ = 0;
+}
+
+int SendSocket::SendHoldMsg() {
+ if (hold_msg_len_ > 0) {
+ int val = Send(hold_msg_, hold_msg_len_);
+ hold_msg_len_ = 0;
+ return val;
+ }
+ return -1;
+}
+
+} // namespace aos
+
diff --git a/aos/common/network/SendSocket.h b/aos/common/network/SendSocket.h
new file mode 100644
index 0000000..6d3feb1
--- /dev/null
+++ b/aos/common/network/SendSocket.h
@@ -0,0 +1,28 @@
+#ifndef AOS_NETWORK_SEND_SOCKET_H_
+#define AOS_NETWORK_SEND_SOCKET_H_
+
+#include "Socket.h"
+
+namespace aos {
+
+class SendSocket : public Socket {
+ public:
+ //inline int Send(const void *buf, int length) { return Socket::Send(buf, length); }
+ // Connect must be called before use.
+ SendSocket() {}
+ // Calls Connect automatically.
+ SendSocket(NetworkPort port, const char *robot_ip) {
+ Connect(port, robot_ip);
+ }
+ int Connect(NetworkPort port, const char *robot_ip, int type = SOCK_DGRAM);
+
+ static const size_t MAX_MSG = 4096;
+ char hold_msg_[MAX_MSG];
+ size_t hold_msg_len_;
+ int SendHoldMsg();
+};
+
+} // namespace aos
+
+#endif
+
diff --git a/aos/common/network/Socket.cpp b/aos/common/network/Socket.cpp
new file mode 100644
index 0000000..b01bcb8
--- /dev/null
+++ b/aos/common/network/Socket.cpp
@@ -0,0 +1,77 @@
+#include "aos/common/network/Socket.h"
+
+#include <string.h>
+#include <errno.h>
+
+#include "aos/aos_core.h"
+#include "aos/common/network/SocketLibraries.h"
+
+namespace aos {
+
+int Socket::Connect(NetworkPort port, const char *address, int type) {
+ last_ret_ = 0;
+ if ((socket_ = socket(AF_INET, type, 0)) < 0) {
+ LOG(ERROR, "failed to create socket because of %d: %s\n", errno, strerror(errno));
+ return last_ret_ = 1;
+ }
+
+ memset(&addr_, 0, sizeof(addr_));
+ addr_.in.sin_family = AF_INET;
+ addr_.in.sin_port = htons(static_cast<uint16_t>(port));
+#ifndef __VXWORKS__
+ const int failure_return = 0;
+#else
+ const int failure_return = -1;
+#endif
+ if (inet_aton(lame_unconst(address), &addr_.in.sin_addr) == failure_return) {
+ LOG(ERROR, "Invalid IP address '%s' because of %d: %s\n", address,
+ errno, strerror(errno));
+ return last_ret_ = -1;
+ }
+
+ return last_ret_ = 0;
+}
+Socket::Socket() : socket_(-1), last_ret_(2) {}
+Socket::~Socket() {
+ close(socket_);
+}
+
+void Socket::Reset() {
+ if (socket_ != -1) {
+ close(socket_);
+ socket_ = -1;
+ }
+ last_ret_ = 0;
+}
+
+int Socket::Recv(void *buf, int length) {
+ const int ret = recv(socket_, static_cast<char *>(buf), length, 0);
+ last_ret_ = (ret == -1) ? -1 : 0;
+ return ret;
+}
+int Socket::Recv(void *buf, int length, long usec) {
+ timeval tv;
+ tv.tv_sec = 0;
+ tv.tv_usec = usec;
+ fd_set fds;
+ FD_ZERO(&fds);
+ FD_SET(socket_, &fds);
+ switch (select(FD_SETSIZE, &fds, NULL, NULL, &tv)) {
+ case 1:
+ return Recv(buf, length);
+ case 0:
+ return last_ret_ = 0;
+ default:
+ perror("select on socket to receive from failed");
+ return last_ret_ = -1;
+ }
+}
+int Socket::Send(const void *buf, int length) {
+ const int ret = write(socket_,
+ lame_unconst(static_cast<const char *>(buf)), length);
+ //const int ret = length;
+ last_ret_ = (ret == -1) ? -1 : 0;
+ return ret;
+}
+
+} // namespace aos
diff --git a/aos/common/network/Socket.h b/aos/common/network/Socket.h
new file mode 100644
index 0000000..ceee754
--- /dev/null
+++ b/aos/common/network/Socket.h
@@ -0,0 +1,42 @@
+#ifndef AOS_NETWORK_SOCKET_H_
+#define AOS_NETWORK_SOCKET_H_
+
+#include <sys/socket.h>
+#include <sys/types.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <stdio.h>
+#include "aos/common/Configuration.h"
+
+namespace aos {
+
+class Socket {
+ public:
+ int LastStatus() const { return last_ret_; }
+
+ int Send(const void *buf, int length);
+ int Recv(void *buf, int length);
+ int Recv(void *buf, int length, long usec); // returns 0 if timed out
+ protected:
+ int Connect(NetworkPort port, const char *address, int type = SOCK_DGRAM);
+ Socket();
+ ~Socket();
+
+ // Resets socket_ and last_ret_.
+ void Reset();
+
+ union {
+ sockaddr_in in;
+ sockaddr addr;
+ } addr_; // filled in by Connect
+
+ int socket_;
+ int last_ret_;
+};
+
+} // namespace aos
+
+#endif
+
diff --git a/aos/common/network/SocketLibraries.h b/aos/common/network/SocketLibraries.h
new file mode 100644
index 0000000..7e8825a
--- /dev/null
+++ b/aos/common/network/SocketLibraries.h
@@ -0,0 +1,16 @@
+// Includes the socket libraries under vxworks and linux.
+// Defines a lame_unconst macro for the vxworks functions that need it.
+
+#ifndef __VXWORKS__
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sys/select.h>
+#define lame_unconst(a) a
+#else
+#include <inetLib.h>
+#include <sockLib.h>
+#include <selectLib.h>
+// Vxworks is missing the const in a couple of its function signatures, so...
+#define lame_unconst(a) const_cast<char *>(a)
+#endif
+
diff --git a/aos/common/network/network.gyp b/aos/common/network/network.gyp
new file mode 100644
index 0000000..ca3e653
--- /dev/null
+++ b/aos/common/network/network.gyp
@@ -0,0 +1,56 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'socket_so',
+ 'type': 'shared_library',
+ 'variables': {'no_rsync': 1},
+ 'sources': [
+ 'ReceiveSocket.cpp',
+ 'SendSocket.cpp',
+ 'Socket.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:aos_shared_lib',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/build/aos.gyp:aos_shared_lib',
+ ],
+ 'conditions': [
+ ['OS=="crio"', {
+ 'dependencies': [
+ '<(EXTERNALS):WPILib',
+ ]}
+ ],
+ ],
+ 'direct_dependent_settings': {
+ 'variables': {
+ 'jni_libs': [
+ 'socket_so',
+ ],
+ },
+ },
+ },
+ {
+ 'target_name': 'socket',
+ 'type': 'static_library',
+ 'sources': [
+ 'ReceiveSocket.cpp',
+ 'SendSocket.cpp',
+ 'Socket.cpp',
+ ],
+ 'conditions': [
+ ['OS=="crio"', {
+ 'dependencies': [
+ '<(EXTERNALS):WPILib',
+ ]}
+ ],
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:logging',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/build/aos.gyp:logging',
+ ],
+ },
+ ],
+}
diff --git a/aos/common/queue.cc b/aos/common/queue.cc
new file mode 100644
index 0000000..7e7f2a1
--- /dev/null
+++ b/aos/common/queue.cc
@@ -0,0 +1,37 @@
+#include "aos/common/queue.h"
+
+#include "aos/common/byteorder.h"
+#include "aos/common/inttypes.h"
+
+namespace aos {
+
+void Message::Zero() {
+ sent_time.set_sec(0);
+ sent_time.set_nsec(0);
+}
+
+size_t Message::Deserialize(const char *buffer) {
+ int32_t sec;
+ int32_t nsec;
+ to_host(&buffer[0], &sec);
+ to_host(&buffer[4], &nsec);
+ sent_time.set_sec(sec);
+ sent_time.set_nsec(nsec);
+ return Size();
+}
+// Serializes the common fields into the buffer.
+size_t Message::Serialize(char *buffer) const {
+ // TODO(aschuh): to_network shouldn't need a pointer.
+ int32_t sec = sent_time.sec();
+ int32_t nsec = sent_time.nsec();
+ to_network(&sec, &buffer[0]);
+ to_network(&nsec, &buffer[4]);
+ return Size();
+}
+
+size_t Message::Print(char *buffer, int length) const {
+ return snprintf(buffer, length, "%"PRId32".%09"PRId32"s",
+ sent_time.sec(), sent_time.nsec());
+}
+
+} // namespace aos
diff --git a/aos/common/queue.h b/aos/common/queue.h
new file mode 100644
index 0000000..7b38e67
--- /dev/null
+++ b/aos/common/queue.h
@@ -0,0 +1,313 @@
+#ifndef AOS_COMMON_QUEUE_H_
+#define AOS_COMMON_QUEUE_H_
+
+#include <assert.h>
+
+#if defined(__VXWORKS__) || defined(__TEST_VXWORKS__)
+#define USE_UNSAFE
+#else
+#undef USE_UNSAFE
+#endif
+
+#include "aos/aos_core.h"
+#include "aos/common/macros.h"
+#ifndef USE_UNSAFE
+#include "aos/atom_code/ipc_lib/queue.h"
+#endif // USE_UNSAFE
+#include "aos/common/time.h"
+
+
+namespace aos {
+
+// This class is a base class for all messages sent over queues.
+class Message {
+ public:
+ typedef ::aos::time::Time Time;
+ // The time that the message was sent at.
+ Time sent_time;
+
+ Message() : sent_time(0, 0) {}
+
+ // Zeros out the time.
+ void Zero();
+ // Returns the size of the message in bytes.
+ static size_t Size() { return sizeof(Time); }
+
+ // Deserializes the common fields from the buffer.
+ size_t Deserialize(const char *buffer);
+ // Serializes the common fields into the buffer.
+ size_t Serialize(char *buffer) const;
+
+ // Populates sent_time with the current time.
+ void SetTimeToNow() { sent_time = Time::Now(); }
+
+ // Writes the contents of the message to the provided buffer.
+ size_t Print(char *buffer, int length) const;
+};
+
+template <class T> class Queue;
+template <class T> class MessageBuilder;
+template <class T> class ScopedMessagePtr;
+#ifndef USE_UNSAFE
+template <class T> class SafeMessageBuilder;
+template <class T> class SafeScopedMessagePtr;
+#endif // USE_UNSAFE
+
+// A ScopedMessagePtr<> manages a queue message pointer.
+// It frees it properly when the ScopedMessagePtr<> goes out of scope or gets
+// sent. By design, there is no way to get the ScopedMessagePtr to release the
+// message pointer.
+template <class T>
+class ScopedMessagePtr {
+ public:
+ // Returns a pointer to the message.
+ // This stays valid until Send or the destructor have been called.
+ const T *get() const { return msg_; }
+ T *get() { return msg_; }
+
+ const T &operator*() const {
+ const T *msg = get();
+ assert(msg != NULL);
+ return *msg;
+ }
+
+ T &operator*() {
+ T *msg = get();
+ assert(msg != NULL);
+ return *msg;
+ }
+
+ const T *operator->() const {
+ const T *msg = get();
+ assert(msg != NULL);
+ return msg;
+ }
+
+ T *operator->() {
+ T *msg = get();
+ assert(msg != NULL);
+ return msg;
+ }
+
+ operator bool() {
+ return msg_ != NULL;
+ }
+
+ // Sends the message and removes our reference to it.
+ // If the queue is full, over-ride the oldest message in it with our new
+ // message.
+ // Returns true on success, and false otherwise.
+ // The message will be freed.
+ bool Send();
+
+ // Sends the message and removes our reference to it.
+ // If the queue is full, block until it is no longer full.
+ // Returns true on success, and false otherwise.
+ // The message will be freed.
+ bool SendBlocking();
+
+ // Frees the contained message.
+ ~ScopedMessagePtr() {
+ reset();
+ }
+
+#ifndef SWIG
+ // Implements a move constructor. This only takes rvalue references
+ // because we want to allow someone to say
+ // ScopedMessagePtr<X> ptr = queue.MakeMessage();
+ // but we don't want to allow them to then say
+ // ScopedMessagePtr<X> new_ptr = ptr;
+ // And, if they do actually want to copy the pointer, then it will correctly
+ // clear out the source so there aren't 2 pointers to the message lying
+ // around.
+ ScopedMessagePtr(ScopedMessagePtr<T> &&ptr)
+ :
+#ifndef USE_UNSAFE
+ queue_(ptr.queue_),
+#endif // USE_UNSAFE
+ msg_(ptr.msg_) {
+ ptr.msg_ = NULL;
+ }
+#endif // SWIG
+
+ private:
+ // Provide access to set_queue and the constructor for init.
+ friend class aos::Queue<typename std::remove_const<T>::type>;
+ // Provide access to the copy constructor for MakeWithBuilder.
+ friend class aos::MessageBuilder<T>;
+
+#ifndef USE_UNSAFE
+ // Only Queue should be able to build a queue.
+ ScopedMessagePtr(aos_queue *queue, T *msg)
+ : queue_(queue), msg_(msg) {}
+#else
+ ScopedMessagePtr(T *msg)
+ : msg_(msg) {}
+#endif // USE_UNSAFE
+
+ // Sets the pointer to msg, freeing the old value if it was there.
+ // This is private because nobody should be able to get a pointer to a message
+ // that needs to be scoped without using the queue.
+ void reset(T *msg = NULL);
+
+#ifndef USE_UNSAFE
+ // Sets the queue that owns this message.
+ void set_queue(aos_queue *queue) { queue_ = queue; }
+
+ // The queue that the message is a part of.
+ aos_queue *queue_;
+#endif // USE_UNSAFE
+ // The message or NULL.
+ T *msg_;
+
+ // Protect evil constructors.
+ DISALLOW_COPY_AND_ASSIGN(ScopedMessagePtr<T>);
+};
+
+// Specializations for the Builders will be automatically generated in the .q.h
+// header files with all of the handy builder methods.
+// This builder uses an actual shm message pointer, which is more efficient and
+// more dangerous than the linux only SafeMessageBuilder.
+template <class T>
+class MessageBuilder {
+ public:
+ typedef T Message;
+ bool Send();
+};
+
+// TODO(aschuh): Base class
+// T must be a Message with the same format as the messages generated by
+// the q files.
+template <class T>
+class Queue {
+ public:
+ typedef T Message;
+
+ Queue(const char *queue_name)
+ : queue_name_(queue_name),
+#ifdef USE_UNSAFE
+ queue_msg_(&msg_)
+#else
+ queue_(NULL),
+ queue_msg_(NULL, NULL)
+#endif // USE_UNSAFE
+ {
+ static_assert(shm_ok<T>::value,
+ "The provided message type can't be put in shmem.");
+ }
+
+ // Initializes the queue. This may optionally be called to do any one time
+ // work before sending information, and may be be called mulitple times.
+ // Init will be called when a message is sent, but this will cause sending to
+ // take a different amount of time the first cycle.
+ void Init();
+
+ // Fetches the next message from the queue.
+ // Returns true if there was a new message available and we successfully
+ // fetched it. This removes the message from the queue for all readers.
+ // TODO(aschuh): Fix this to use a different way of fetching messages so other
+ // readers can also FetchNext.
+ bool FetchNext();
+ bool FetchNextBlocking();
+
+ // Fetches the last message from the queue.
+ // Returns true if there was a new message available and we successfully
+ // fetched it.
+ bool FetchLatest();
+
+ // Returns the age of the message.
+ const time::Time Age() { return time::Time::Now() - queue_msg_->sent_time; }
+
+ // Returns true if the latest value in the queue is newer than age mseconds.
+ bool IsNewerThanMS(int age) {
+ // TODO(aschuh): Log very verbosely if something is _ever_ stale;
+ if (get() != NULL) {
+ return Age() < time::Time::InMS(age);
+ } else {
+ return false;
+ }
+ }
+
+ // Returns a pointer to the current message.
+ // This pointer will be valid until a new message is fetched.
+ const T *get() const { return queue_msg_.get(); }
+
+ // Returns a reference to the message.
+ // The message will be valid until a new message is fetched.
+ const T &operator*() const {
+ const T *msg = get();
+ assert(msg != NULL);
+ return *msg;
+ }
+
+ // Returns a pointer to the current message.
+ // This pointer will be valid until a new message is fetched.
+ const T *operator->() const {
+ const T *msg = get();
+ assert(msg != NULL);
+ return msg;
+ }
+
+#ifndef USE_UNSAFE
+ // Returns a scoped_ptr containing a message.
+ // GCC will optimize away the copy constructor, so this is safe.
+ SafeScopedMessagePtr<T> SafeMakeMessage();
+
+ // Returns a message builder that contains a pre-allocated message.
+ aos::SafeMessageBuilder<T> SafeMakeWithBuilder();
+#endif // USE_UNSAFE
+
+#ifndef SWIG
+ // Returns a scoped_ptr containing a message.
+ // GCC will optimize away the copy constructor, so this is safe.
+ ScopedMessagePtr<T> MakeMessage();
+
+ // Returns a message builder that contains a pre-allocated message.
+ aos::MessageBuilder<T> MakeWithBuilder();
+#endif // SWIG
+
+ const char *name() const { return queue_name_; }
+
+ private:
+ const char *queue_name_;
+
+#ifdef USE_UNSAFE
+ // The unsafe queue only has 1 entry and no safety, so 1 message is fine.
+ T msg_;
+#else
+ T *MakeRawMessage();
+ // Pointer to the queue that this object fetches from.
+ aos_queue *queue_;
+#endif
+ // Scoped pointer holding the latest message or NULL.
+ ScopedMessagePtr<const T> queue_msg_;
+ DISALLOW_COPY_AND_ASSIGN(Queue<T>);
+};
+
+// Base class for all queue groups.
+class QueueGroup {
+ public:
+ // Constructs a queue group given its name and a unique hash of the name and
+ // type.
+ QueueGroup(const char *name, uint32_t hash) : name_(name), hash_(hash) {}
+
+ // Returns the name of the queue group.
+ const char *name() const { return name_.c_str(); }
+ // Returns a unique hash representing this instance of the queue group.
+ uint32_t hash() const { return hash_; }
+
+ private:
+ std::string name_;
+ uint32_t hash_;
+};
+
+} // namespace aos
+
+#ifdef USE_UNSAFE
+#include "aos/crio/queue-tmpl.h"
+#else
+#include "aos/atom_code/queue-tmpl.h"
+#endif
+#undef USE_UNSAFE
+
+#endif // AOS_COMMON_QUEUE_H_
diff --git a/aos/common/queue_test.cc b/aos/common/queue_test.cc
new file mode 100644
index 0000000..b24fcd5
--- /dev/null
+++ b/aos/common/queue_test.cc
@@ -0,0 +1,327 @@
+#include <unistd.h>
+
+#include <memory>
+
+#include "gtest/gtest.h"
+#include "aos/common/test_queue.q.h"
+#include "aos/common/queue_testutils.h"
+
+
+using ::aos::time::Time;
+
+namespace aos {
+namespace common {
+
+// TODO(aschuh): Pull this out somewhere and test it.
+class Thread {
+ public:
+ Thread () {
+ started_ = false;
+ joined_ = false;
+ }
+
+ ~Thread() {
+ if (!joined_ && started_) {
+ assert(false);
+ }
+ }
+
+ void Start() {
+ assert(!started_);
+ pthread_create(&thread_, NULL, &Thread::StaticRun, this);
+ started_ = true;
+ }
+
+ virtual void Run() = 0;
+
+ void Join() {
+ assert(!joined_);
+ pthread_join(thread_, NULL);
+ joined_ = true;
+ }
+ private:
+ static void *StaticRun(void *thread_class) {
+ static_cast<Thread *>(thread_class)->Run();
+ return NULL;
+ }
+
+ pthread_t thread_;
+ bool started_;
+ bool joined_;
+
+ DISALLOW_COPY_AND_ASSIGN(Thread);
+};
+
+namespace testing {
+
+class QueueTest : public ::testing::Test {
+ protected:
+ GlobalCoreInstance my_core;
+ // Create a new instance of the test queue so that it invalidates the queue
+ // that it points to. Otherwise, we will have a pointer to shared memory that
+ // is no longer valid.
+ ::aos::Queue<TestingMessage> my_test_queue;
+
+ QueueTest() : my_test_queue(".aos.common.testing.test_queue") {}
+};
+
+class MyThread : public Thread {
+ public:
+ MyThread() : threaded_test_queue(".aos.common.testing.test_queue") {}
+
+ virtual void Run() {
+ ASSERT_TRUE(threaded_test_queue.FetchNextBlocking());
+ EXPECT_TRUE(threaded_test_queue->test_bool);
+ EXPECT_EQ(0x971, threaded_test_queue->test_int);
+ }
+
+ ::aos::Queue<TestingMessage> threaded_test_queue;
+ private:
+ DISALLOW_COPY_AND_ASSIGN(MyThread);
+};
+
+
+// Tests that we can send a message to another thread and it blocking receives
+// it at the correct time.
+TEST_F(QueueTest, FetchBlocking) {
+ MyThread t;
+ t.Start();
+ usleep(50000);
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
+ t.Join();
+ EXPECT_EQ(true, t.threaded_test_queue.IsNewerThanMS(20));
+}
+
+// Tests that we can send a message with the message pointer and get it back.
+TEST_F(QueueTest, SendMessage) {
+ ScopedMessagePtr<TestingMessage> msg = my_test_queue.MakeMessage();
+ msg->test_bool = true;
+ msg->test_int = 0x971;
+ msg.Send();
+
+ ASSERT_TRUE(my_test_queue.FetchLatest());
+ EXPECT_TRUE(my_test_queue->test_bool);
+ EXPECT_EQ(0x971, my_test_queue->test_int);
+}
+
+// Tests that we can send a message with the message pointer and get it back.
+TEST_F(QueueTest, SendMessageBlockingSafe) {
+ SafeScopedMessagePtr<TestingMessage> msg = my_test_queue.SafeMakeMessage();
+ msg->test_bool = true;
+ msg->test_int = 0x971;
+ ASSERT_TRUE(msg.SendBlocking());
+
+ ASSERT_TRUE(my_test_queue.FetchLatest());
+ EXPECT_TRUE(my_test_queue->test_bool);
+ EXPECT_EQ(0x971, my_test_queue->test_int);
+}
+
+// Tests that we can send a message with the message pointer and get it back.
+TEST_F(QueueTest, SendMessageSafe) {
+ SafeScopedMessagePtr<TestingMessage> msg = my_test_queue.SafeMakeMessage();
+ msg->test_bool = true;
+ msg->test_int = 0x971;
+ msg.Send();
+
+ ASSERT_TRUE(my_test_queue.FetchLatest());
+ EXPECT_TRUE(my_test_queue->test_bool);
+ EXPECT_EQ(0x971, my_test_queue->test_int);
+}
+
+// Tests that we can send a message with the builder and get it back.
+TEST_F(QueueTest, SendWithBuilder) {
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
+
+ ASSERT_TRUE(my_test_queue.FetchLatest());
+ EXPECT_EQ(true, my_test_queue->test_bool);
+ EXPECT_EQ(0x971, my_test_queue->test_int);
+ EXPECT_EQ(true, my_test_queue.IsNewerThanMS(10000));
+}
+
+// Tests that various pointer deref functions at least seem to work.
+TEST_F(QueueTest, PointerDeref) {
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
+
+ ASSERT_TRUE(my_test_queue.FetchLatest());
+ const TestingMessage *msg_ptr = my_test_queue.get();
+ ASSERT_NE(static_cast<TestingMessage*>(NULL), msg_ptr);
+ EXPECT_EQ(0x971, msg_ptr->test_int);
+ EXPECT_EQ(msg_ptr, &(*my_test_queue));
+}
+
+// Tests that FetchNext doesn't miss any messages.
+TEST_F(QueueTest, FetchNext) {
+ for (int i = 0; i < 10; ++i) {
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(i).Send();
+ }
+
+ for (int i = 0; i < 10; ++i) {
+ ASSERT_TRUE(my_test_queue.FetchNext());
+ EXPECT_EQ(i, my_test_queue->test_int);
+ }
+}
+
+// Tests that FetchLatest skips a missing message.
+TEST_F(QueueTest, FetchLatest) {
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x254).Send();
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
+
+ ASSERT_TRUE(my_test_queue.FetchLatest());
+ EXPECT_EQ(0x971, my_test_queue->test_int);
+}
+
+// Tests that FetchLatest works with multiple readers.
+TEST_F(QueueTest, FetchLatestMultiple) {
+ ::aos::Queue<TestingMessage> my_second_test_queue(
+ ".aos.common.testing.test_queue");
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x254).Send();
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
+
+ ASSERT_TRUE(my_test_queue.FetchLatest());
+ EXPECT_EQ(0x971, my_test_queue->test_int);
+ ASSERT_TRUE(my_second_test_queue.FetchLatest());
+ ASSERT_TRUE(my_second_test_queue.get() != NULL);
+ EXPECT_EQ(0x971, my_second_test_queue->test_int);
+}
+
+
+// Tests that fetching without a new message returns false.
+TEST_F(QueueTest, FetchLatestWithoutMessage) {
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x254).Send();
+ EXPECT_TRUE(my_test_queue.FetchLatest());
+ EXPECT_FALSE(my_test_queue.FetchLatest());
+ EXPECT_FALSE(my_test_queue.FetchLatest());
+ EXPECT_EQ(0x254, my_test_queue->test_int);
+}
+
+// Tests that fetching without a message returns false.
+TEST_F(QueueTest, FetchOnFreshQueue) {
+ EXPECT_FALSE(my_test_queue.FetchLatest());
+ EXPECT_EQ(static_cast<TestingMessage*>(NULL), my_test_queue.get());
+}
+
+// Tests that fetch next without a message returns false.
+TEST_F(QueueTest, FetchNextOnFreshQueue) {
+ EXPECT_FALSE(my_test_queue.FetchNext());
+ EXPECT_EQ(static_cast<TestingMessage*>(NULL), my_test_queue.get());
+}
+
+// Tests that fetch next without a new message returns false.
+TEST_F(QueueTest, FetchNextWithoutMessage) {
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x254).Send();
+ EXPECT_TRUE(my_test_queue.FetchNext());
+ EXPECT_FALSE(my_test_queue.FetchNext());
+ EXPECT_NE(static_cast<TestingMessage*>(NULL), my_test_queue.get());
+}
+
+// Tests that age makes some sense.
+TEST_F(QueueTest, Age) {
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
+
+ ASSERT_TRUE(my_test_queue.FetchLatest());
+ EXPECT_TRUE(my_test_queue.IsNewerThanMS(100));
+ const Time age = my_test_queue.Age();
+ EXPECT_EQ(0, age.sec());
+ EXPECT_GE(100000000, age.nsec());
+}
+
+
+class GroupTest : public ::testing::Test {
+ protected:
+ GlobalCoreInstance my_core;
+ // Create a new instance of the test group so that it invalidates the queue
+ // that it points to. Otherwise, we will have a pointer to shared memory that
+ // is no longer valid.
+ TwoQueues my_test_queuegroup;
+
+ GroupTest()
+ : my_test_queuegroup(".aos.common.testing.test_queuegroup",
+ 0x20561114,
+ ".aos.common.testing.test_queuegroup.first",
+ ".aos.common.testing.test_queuegroup.second") {}
+};
+
+// Tests that the hash gets preserved.
+TEST_F(GroupTest, Hash) {
+ EXPECT_EQ(static_cast<uint32_t>(0x20561114), my_test_queuegroup.hash());
+}
+
+// Tests that the hash works.
+TEST_F(GroupTest, RealHash) {
+ EXPECT_EQ(static_cast<uint32_t>(0x5b25097f), test_queuegroup.hash());
+}
+
+// Tests that name works.
+TEST_F(GroupTest, Name) {
+ EXPECT_EQ(std::string(".aos.common.testing.test_queuegroup"),
+ std::string(my_test_queuegroup.name()));
+}
+
+
+class MessageTest : public ::testing::Test {
+ public:
+ TestingMessage msg;
+};
+
+TEST_F(MessageTest, Zeroing) {
+ msg.test_bool = true;
+ msg.test_int = 0x254;
+ msg.SetTimeToNow();
+
+ msg.Zero();
+
+ EXPECT_FALSE(msg.test_bool);
+ EXPECT_EQ(0, msg.test_int);
+ EXPECT_EQ(0, msg.sent_time.sec());
+ EXPECT_EQ(0, msg.sent_time.nsec());
+}
+
+TEST_F(MessageTest, Size) {
+ EXPECT_EQ(static_cast<size_t>(13), msg.Size());
+}
+
+TEST_F(MessageTest, Serialize) {
+ char serialized_data[msg.Size()];
+ msg.test_bool = true;
+ msg.test_int = 0x254;
+ msg.SetTimeToNow();
+
+ msg.Serialize(serialized_data);
+
+ TestingMessage new_msg;
+ new_msg.Deserialize(serialized_data);
+
+ EXPECT_EQ(msg.test_bool, new_msg.test_bool);
+ EXPECT_EQ(msg.test_int, new_msg.test_int);
+ EXPECT_EQ(msg.sent_time, new_msg.sent_time);
+}
+
+// Tests that Print prints out a message nicely.
+TEST_F(MessageTest, Print) {
+ char printdata[1024];
+ msg.test_bool = true;
+ msg.test_int = 2056;
+ msg.sent_time = Time(971, 254);
+
+ std::string golden("971.000000254s, t, 2056");
+ EXPECT_EQ(golden.size(), msg.Print(printdata, sizeof(printdata)));
+
+ EXPECT_EQ(golden, std::string(printdata));
+}
+
+// Tests that the hash never changes. If it changes, then someone broke the
+// hash routine or changed the message declaration. Both changes need to be
+// validated by hand.
+TEST_F(MessageTest, Hash) {
+ EXPECT_EQ(static_cast<uint32_t>(0xcf740cc1),
+ static_cast<uint32_t>(TestingMessage::kHash));
+}
+
+TEST_F(MessageTest, SetNow) {
+ msg.SetTimeToNow();
+ EXPECT_LE(msg.sent_time - Time::Now(), Time::InMS(20));
+}
+
+} // namespace testing
+} // namespace common
+} // namespace aos
diff --git a/aos/common/queue_testutils.cc b/aos/common/queue_testutils.cc
new file mode 100644
index 0000000..6cce012
--- /dev/null
+++ b/aos/common/queue_testutils.cc
@@ -0,0 +1,26 @@
+#include "aos/common/queue_testutils.h"
+#include "aos/common/queue.h"
+
+namespace aos {
+namespace common {
+namespace testing {
+
+GlobalCoreInstance::GlobalCoreInstance() {
+ const size_t kCoreSize = 0x100000;
+ global_core = &global_core_data_;
+ global_core->owner = 1;
+ void *memory = malloc(kCoreSize);
+ assert(memory != NULL);
+ memset(memory, 0, kCoreSize);
+
+ assert(aos_core_use_address_as_shared_mem(memory, kCoreSize) == 0);
+}
+
+GlobalCoreInstance::~GlobalCoreInstance() {
+ free(global_core->mem_struct);
+ global_core = NULL;
+}
+
+} // namespace testing
+} // namespace common
+} // namespace aos
diff --git a/aos/common/queue_testutils.h b/aos/common/queue_testutils.h
new file mode 100644
index 0000000..81f1efb
--- /dev/null
+++ b/aos/common/queue_testutils.h
@@ -0,0 +1,18 @@
+#include "aos/common/queue.h"
+
+namespace aos {
+namespace common {
+namespace testing {
+
+class GlobalCoreInstance {
+ public:
+ GlobalCoreInstance();
+ ~GlobalCoreInstance();
+
+ private:
+ struct aos_core global_core_data_;
+};
+
+} // namespace testing
+} // namespace common
+} // namespace aos
diff --git a/aos/common/scoped_fd.h b/aos/common/scoped_fd.h
new file mode 100644
index 0000000..e654d3d
--- /dev/null
+++ b/aos/common/scoped_fd.h
@@ -0,0 +1,38 @@
+#include "aos/common/macros.h"
+
+namespace aos {
+
+// Smart "pointer" (container) for a file descriptor.
+class ScopedFD {
+ public:
+ explicit ScopedFD(int fd = -1) : fd_(fd) {}
+ ~ScopedFD() {
+ Close();
+ }
+ int get() const { return fd_; }
+ int release() {
+ const int r = fd_;
+ fd_ = -1;
+ return r;
+ }
+ void reset(int new_fd = -1) {
+ if (fd_ != new_fd) {
+ Close();
+ fd_ = new_fd;
+ }
+ }
+ operator bool() const { return fd_ != -1; }
+ private:
+ int fd_;
+ void Close() {
+ if (fd_ != -1) {
+ if (close(fd_) == -1) {
+ LOG(WARNING, "close(%d) failed with %d: %s\n", fd_,
+ errno, strerror(errno));
+ }
+ }
+ }
+ DISALLOW_COPY_AND_ASSIGN(ScopedFD);
+};
+
+} // namespace aos
diff --git a/aos/common/scoped_ptr.h b/aos/common/scoped_ptr.h
new file mode 100644
index 0000000..e4df78e
--- /dev/null
+++ b/aos/common/scoped_ptr.h
@@ -0,0 +1,43 @@
+#ifndef AOS_COMMON_SCOPED_PTR_H_
+#define AOS_COMMON_SCOPED_PTR_H_
+
+#include "aos/common/macros.h"
+
+namespace aos {
+
+// A simple scoped_ptr implementation that works under both linux and vxworks.
+template<typename T>
+class scoped_ptr {
+ public:
+ typedef T element_type;
+
+ explicit scoped_ptr(T *p = NULL) : p_(p) {}
+ ~scoped_ptr() {
+ delete p_;
+ }
+
+ T &operator*() const { return *p_; }
+ T *operator->() const { return p_; }
+ T *get() const { return p_; }
+
+ operator bool() const { return p_ != NULL; }
+
+ void swap(scoped_ptr<T> &other) {
+ T *temp = other.p_;
+ other.p_ = p_;
+ p_ = other.p_;
+ }
+ void reset(T *p = NULL) {
+ if (p_ != NULL) delete p_;
+ p_ = p;
+ }
+
+ private:
+ T *p_;
+
+ DISALLOW_COPY_AND_ASSIGN(scoped_ptr<T>);
+};
+
+} // namespace aos
+
+#endif // AOS_COMMON_SCOPED_PTR_H_
diff --git a/aos/common/test_queue.q b/aos/common/test_queue.q
new file mode 100644
index 0000000..a7b441f
--- /dev/null
+++ b/aos/common/test_queue.q
@@ -0,0 +1,21 @@
+package aos.common.testing;
+
+message TestingMessage {
+ bool test_bool;
+ int32_t test_int;
+};
+
+message OtherTestingMessage {
+ bool test_bool;
+ int32_t test_int;
+ double test_double;
+};
+
+queue TestingMessage test_queue;
+
+queue_group TwoQueues {
+ queue TestingMessage first;
+ queue OtherTestingMessage second;
+};
+
+queue_group TwoQueues test_queuegroup;
diff --git a/aos/common/time.cc b/aos/common/time.cc
new file mode 100644
index 0000000..1d97b80
--- /dev/null
+++ b/aos/common/time.cc
@@ -0,0 +1,166 @@
+#include "aos/common/time.h"
+
+#ifdef __VXWORKS__
+#include <taskLib.h>
+#endif
+
+#include "aos/common/logging/logging.h"
+#include "aos/common/inttypes.h"
+
+namespace aos {
+namespace time {
+
+Time Time::Now(clockid_t clock) {
+ timespec temp;
+ if (clock_gettime(clock, &temp) != 0) {
+ // TODO(aschuh): There needs to be a pluggable low level logging interface
+ // so we can break this dependency loop. This also would help during
+ // startup.
+ LOG(FATAL, "clock_gettime(%jd, %p) failed with %d: %s\n",
+ static_cast<uintmax_t>(clock), &temp, errno, strerror(errno));
+ }
+ return Time(temp);
+}
+void Time::Check() {
+ if (nsec_ >= kNSecInSec || nsec_ < 0) {
+ LOG(FATAL, "0 <= nsec_(%"PRId32") < %"PRId32" isn't true.\n",
+ nsec_, kNSecInSec);
+ }
+ static_assert(aos::shm_ok<Time>::value,
+ "it should be able to go through shared memory");
+}
+
+Time &Time::operator+=(const Time &rhs) {
+ sec_ += rhs.sec_;
+ nsec_ += rhs.nsec_;
+ if (nsec_ >= kNSecInSec) {
+ nsec_ -= kNSecInSec;
+ sec_ += 1;
+ }
+ return *this;
+}
+const Time Time::operator+(const Time &rhs) const {
+ return Time(*this) += rhs;
+}
+Time &Time::operator-=(const Time &rhs) {
+ sec_ -= rhs.sec_;
+ nsec_ -= rhs.nsec_;
+ if (nsec_ < 0) {
+ nsec_ += kNSecInSec;
+ sec_ -= 1;
+ }
+ return *this;
+}
+const Time Time::operator-(const Time &rhs) const {
+ return Time(*this) -= rhs;
+}
+Time &Time::operator*=(int32_t rhs) {
+ const int64_t temp = static_cast<int64_t>(nsec_) *
+ static_cast<int64_t>(rhs);
+ sec_ *= rhs; // better not overflow, or the result is just too big
+ nsec_ = temp % kNSecInSec;
+ sec_ += (temp - nsec_) / kNSecInSec;
+ return *this;
+}
+const Time Time::operator*(int32_t rhs) const {
+ return Time(*this) *= rhs;
+}
+Time &Time::operator/=(int32_t rhs) {
+ nsec_ = (sec_ % rhs) * (kNSecInSec / rhs) + nsec_ / rhs;
+ sec_ /= rhs;
+ return *this;
+}
+const Time Time::operator/(int32_t rhs) const {
+ return Time(*this) /= rhs;
+}
+Time &Time::operator%=(int32_t rhs) {
+ nsec_ = ToNSec() % rhs;
+ const int wraps = nsec_ / kNSecInSec;
+ sec_ = wraps;
+ nsec_ -= kNSecInSec * wraps;
+ return *this;
+}
+const Time Time::operator%(int32_t rhs) const {
+ return Time(*this) %= rhs;
+}
+
+bool Time::operator==(const Time &rhs) const {
+ return sec_ == rhs.sec_ && nsec_ == rhs.nsec_;
+}
+bool Time::operator!=(const Time &rhs) const {
+ return !(*this == rhs);
+}
+bool Time::operator<(const Time &rhs) const {
+ return sec_ < rhs.sec_ || (sec_ == rhs.sec_ && nsec_ < rhs.nsec_);
+}
+bool Time::operator>(const Time &rhs) const {
+ return sec_ > rhs.sec_ || (sec_ == rhs.sec_ && nsec_ > rhs.nsec_);
+}
+bool Time::operator<=(const Time &rhs) const {
+ return sec_ < rhs.sec_ || (sec_ == rhs.sec_ && nsec_ <= rhs.nsec_);
+}
+bool Time::operator>=(const Time &rhs) const {
+ return sec_ > rhs.sec_ || (sec_ == rhs.sec_ && nsec_ >= rhs.nsec_);
+}
+
+bool Time::IsWithin(const Time &other, int64_t amount) const {
+ const int64_t temp = ToNSec() - other.ToNSec();
+ return temp <= amount && temp >= -amount;
+}
+
+std::ostream &operator<<(std::ostream &os, const Time& time) {
+ return os << "Time{" << time.sec_ << "s, " << time.nsec_ << "ns}";
+}
+
+void SleepFor(const Time &time, clockid_t clock) {
+#ifdef __VXWORKS__
+ SleepUntil(Time::Now(clock) + time, clock);
+#else
+ timespec converted(time.ToTimespec()), remaining;
+ int failure = EINTR;
+ do {
+ // This checks whether the last time through the loop actually failed or got
+ // interrupted.
+ if (failure != EINTR) {
+ LOG(FATAL, "clock_nanosleep(%jd, 0, %p, %p) returned %d: %s\n",
+ static_cast<intmax_t>(clock), &converted, &remaining,
+ failure, strerror(failure));
+ }
+ failure = clock_nanosleep(clock, 0, &converted, &remaining);
+ memcpy(&converted, &remaining, sizeof(converted));
+ } while (failure != 0);
+#endif
+}
+
+void SleepUntil(const Time &time, clockid_t clock) {
+#ifdef __VXWORKS__
+ if (clock != CLOCK_REALTIME) {
+ LOG(FATAL, "vxworks only supports CLOCK_REALTIME\n");
+ }
+ // Vxworks nanosleep is definitely broken (fails horribly at doing remaining
+ // right), and I don't really want to know how else it's broken, so I'm using
+ // taskDelay instead because that's simpler.
+ // The +1 is because sleep functions are supposed to sleep for at least the
+ // requested amount, so we have to round up to the next clock tick.
+ while (taskDelay((time - Time::Now(clock)).ToTicks() + 1) != 0) {
+ if (errno != EINTR) {
+ LOG(FATAL, "taskDelay(some ticks) failed with %d: %s\n",
+ errno, strerror(errno));
+ }
+ }
+#else
+ timespec converted(time.ToTimespec());
+ int failure;
+ while ((failure = clock_nanosleep(clock, TIMER_ABSTIME,
+ &converted, NULL)) != 0) {
+ if (failure != EINTR) {
+ LOG(FATAL, "clock_nanosleep(%jd, TIMER_ABSTIME, %p, NULL)"
+ " returned %d: %s\n", static_cast<intmax_t>(clock), &converted,
+ failure, strerror(failure));
+ }
+ }
+#endif
+}
+
+} // namespace time
+} // namespace aos
diff --git a/aos/common/time.h b/aos/common/time.h
new file mode 100644
index 0000000..57c5f26
--- /dev/null
+++ b/aos/common/time.h
@@ -0,0 +1,159 @@
+#ifndef AOS_COMMON_TIME_H_
+#define AOS_COMMON_TIME_H_
+
+#include <stdint.h>
+#include <time.h>
+
+#ifndef __VXWORKS__
+#include <type_traits>
+#else
+#include <sysLib.h>
+#endif
+#include <ostream>
+
+#include "aos/aos_stdint.h"
+#include "aos/common/type_traits.h"
+
+namespace aos {
+namespace time {
+
+// A nice structure for representing times.
+// 0 <= nsec_ < kNSecInSec should always be true. All functions here will make
+// sure that that is true if it was on all inputs (including *this).
+//
+// The arithmetic and comparison operators are overloaded because they make
+// complete sense and are very useful. The default copy and assignment stuff is
+// left because it works fine. Multiplication and division of Times by Times are
+// not implemented because I can't think of any uses for them and there are
+// multiple ways to do it.
+struct Time {
+ public:
+ static const int32_t kNSecInSec = 1000000000;
+ static const int32_t kNSecInMSec = 1000000;
+ static const int32_t kNSecInUSec = 1000;
+ static const int32_t kMSecInSec = 1000;
+ static const int32_t kUSecInSec = 1000000;
+ Time(int32_t sec, int32_t nsec) : sec_(sec), nsec_(nsec) {
+ Check();
+ }
+ #ifndef SWIG
+ explicit Time(const struct timespec &value)
+ : sec_(value.tv_sec), nsec_(value.tv_nsec) {
+ Check();
+ }
+ struct timespec ToTimespec() const {
+ struct timespec ans;
+ ans.tv_sec = sec_;
+ ans.tv_nsec = nsec_;
+ return ans;
+ }
+ #endif // SWIG
+ // CLOCK_MONOTONIC on the fitpc and CLOCK_REALTIME on the cRIO because the
+ // cRIO doesn't have any others.
+ // CLOCK_REALTIME is the default realtime clock and CLOCK_MONOTONIC doesn't
+ // change when somebody changes the wall clock (like the ntp deamon or
+ // whatever). See clock_gettime(2) for details.
+ //
+ // This is the clock that code that just wants to sleep for a certain amount
+ // of time or measure how long something takes should use.
+ #ifndef __VXWORKS__
+ static const clockid_t kDefaultClock = CLOCK_MONOTONIC;
+ #else
+ static const clockid_t kDefaultClock = CLOCK_REALTIME;
+ #endif
+ // Creates a Time representing the current value of the specified clock or
+ // dies.
+ static Time Now(clockid_t clock = kDefaultClock);
+
+ // Constructs a Time representing seconds.
+ static Time InSeconds(double seconds) {
+ return Time(static_cast<int32_t>(seconds),
+ (seconds - static_cast<int32_t>(seconds)) * kNSecInSec);
+ }
+
+ // Constructs a time representing microseconds.
+ static Time InNS(int64_t nseconds) {
+ return Time(nseconds / static_cast<int64_t>(kNSecInSec),
+ nseconds % kNSecInSec);
+ }
+
+ // Constructs a time representing microseconds.
+ static Time InUS(int useconds) {
+ return Time(useconds / kUSecInSec, (useconds % kUSecInSec) * kNSecInUSec);
+ }
+
+ // Constructs a time representing mseconds.
+ static Time InMS(int mseconds) {
+ return Time(mseconds / kMSecInSec, (mseconds % kMSecInSec) * kNSecInMSec);
+ }
+
+ // Checks whether or not this time is within amount nanoseconds of other.
+ bool IsWithin(const Time &other, int64_t amount) const;
+
+ // Returns the time represented all in nanoseconds.
+ int64_t ToNSec() const {
+ return static_cast<int64_t>(sec_) * static_cast<int64_t>(kNSecInSec) +
+ static_cast<int64_t>(nsec_);
+ }
+#ifdef __VXWORKS__
+ // Returns the time represented all in system clock ticks. The system clock
+ // rate is retrieved using sysClkRateGet().
+ int ToTicks() const {
+ return ToNSec() / static_cast<int64_t>(kNSecInSec / sysClkRateGet());
+ }
+#endif
+
+ // Returns the time represented in milliseconds.
+ int64_t ToMSec() const {
+ return static_cast<int64_t>(sec_) * static_cast<int64_t>(kMSecInSec) +
+ (static_cast<int64_t>(nsec_) / static_cast<int64_t>(kNSecInMSec));
+ }
+
+ #ifndef SWIG
+ Time &operator+=(const Time &rhs);
+ Time &operator-=(const Time &rhs);
+ Time &operator*=(int32_t rhs);
+ Time &operator/=(int32_t rhs);
+ Time &operator%=(int32_t rhs);
+ #endif
+ const Time operator+(const Time &rhs) const;
+ const Time operator-(const Time &rhs) const;
+ const Time operator*(int32_t rhs) const;
+ const Time operator/(int32_t rhs) const;
+ const Time operator%(int32_t rhs) const;
+
+ bool operator==(const Time &rhs) const;
+ bool operator!=(const Time &rhs) const;
+ bool operator<(const Time &rhs) const;
+ bool operator>(const Time &rhs) const;
+ bool operator<=(const Time &rhs) const;
+ bool operator>=(const Time &rhs) const;
+
+ #ifndef SWIG
+ // For gtest etc.
+ friend std::ostream &operator<<(std::ostream &os, const Time &time);
+ #endif // SWIG
+
+ int32_t sec() const { return sec_; }
+ void set_sec(int32_t sec) { sec_ = sec; }
+ int32_t nsec() const { return nsec_; }
+ void set_nsec(int32_t nsec) {
+ nsec_ = nsec;
+ Check();
+ }
+
+ private:
+ int32_t sec_, nsec_;
+ // LOG(FATAL)s if nsec_ is >= kNSecInSec.
+ void Check();
+};
+
+// Sleeps for the amount of time represented by time counted by clock.
+void SleepFor(const Time &time, clockid_t clock = Time::kDefaultClock);
+// Sleeps until clock is at the time represented by time.
+void SleepUntil(const Time &time, clockid_t clock = Time::kDefaultClock);
+
+} // namespace time
+} // namespace aos
+
+#endif // AOS_COMMON_TIME_H_
diff --git a/aos/common/time_test.cc b/aos/common/time_test.cc
new file mode 100644
index 0000000..6587759
--- /dev/null
+++ b/aos/common/time_test.cc
@@ -0,0 +1,132 @@
+#include "aos/common/time.h"
+
+#include "gtest/gtest.h"
+
+#include "aos/common/macros.h"
+
+namespace aos {
+namespace time {
+namespace testing {
+
+TEST(TimeTest, timespecConversions) {
+ timespec start{1234, 5678}; // NOLINT
+ Time time(start);
+ EXPECT_EQ(start.tv_sec, static_cast<signed time_t>(time.sec()));
+ EXPECT_EQ(start.tv_nsec, time.nsec());
+ timespec end = time.ToTimespec();
+ EXPECT_EQ(start.tv_sec, end.tv_sec);
+ EXPECT_EQ(start.tv_nsec, end.tv_nsec);
+}
+
+// It's kind of hard not to test Now and SleepFor at the same time.
+TEST(TimeTest, NowAndSleepFor) {
+ // without this, it tends to fail the first time (ends up sleeping for way
+ // longer than it should the second time, where it actually matters)
+ SleepFor(Time(0, Time::kNSecInSec / 10));
+ Time start = Time::Now();
+ SleepFor(Time(0, Time::kNSecInSec * 2 / 10));
+ EXPECT_TRUE(MACRO_DARG((Time::Now() - start)
+ .IsWithin(Time(0, Time::kNSecInSec * 2 / 10),
+ Time::kNSecInSec / 1000)));
+}
+
+TEST(TimeTest, AbsoluteSleep) {
+ Time start = Time::Now();
+ SleepFor(Time(0, Time::kNSecInSec / 10));
+ SleepUntil((start + Time(0, Time::kNSecInSec * 2 / 10)));
+ EXPECT_TRUE(MACRO_DARG((Time::Now() - start)
+ .IsWithin(Time(0, Time::kNSecInSec * 2 / 10),
+ Time::kNSecInSec / 1000)));
+}
+
+TEST(TimeTest, Addition) {
+ Time t(54, 500);
+ EXPECT_EQ(MACRO_DARG(Time(54, 5500)), t + MACRO_DARG(Time(0, 5000)));
+ EXPECT_EQ(MACRO_DARG(Time(56, 500)), t + MACRO_DARG(Time(2, 0)));
+ EXPECT_EQ(MACRO_DARG(Time(57, 6500)), t + MACRO_DARG(Time(3, 6000)));
+ EXPECT_EQ(MACRO_DARG(Time(50, 300)),
+ t + MACRO_DARG(Time(-5, Time::kNSecInSec - 200)));
+}
+TEST(TimeTest, Subtraction) {
+ Time t(54, 500);
+ EXPECT_EQ(MACRO_DARG(Time(54, 300)), t - MACRO_DARG(Time(0, 200)));
+ EXPECT_EQ(MACRO_DARG(Time(42, 500)), t - MACRO_DARG(Time(12, 0)));
+ EXPECT_EQ(MACRO_DARG(Time(50, 100)), t - MACRO_DARG(Time(4, 400)));
+ EXPECT_EQ(MACRO_DARG(Time(53, 600)),
+ t - MACRO_DARG(Time(0, Time::kNSecInSec - 100)));
+ EXPECT_EQ(MACRO_DARG(Time(55, 800)),
+ t - MACRO_DARG(Time(-2, Time::kNSecInSec - 300)));
+}
+
+TEST(TimeTest, Multiplication) {
+ Time t(54, Time::kNSecInSec / 3);
+ EXPECT_EQ(MACRO_DARG(Time(108, Time::kNSecInSec / 3 * 2)), t * 2);
+ EXPECT_EQ(MACRO_DARG(Time(271, Time::kNSecInSec / 3 * 2 - 1)), t * 5);
+}
+TEST(TimeTest, Division) {
+ EXPECT_EQ(MACRO_DARG(Time(5, Time::kNSecInSec / 10 * 4 + 50)),
+ MACRO_DARG(Time(54, 500)) / 10);
+}
+
+TEST(TimeTest, Comparisons) {
+ EXPECT_TRUE(MACRO_DARG(Time(971, 254) > Time(971, 253)));
+ EXPECT_TRUE(MACRO_DARG(Time(971, 254) >= Time(971, 253)));
+ EXPECT_TRUE(MACRO_DARG(Time(971, 254) < Time(971, 255)));
+ EXPECT_TRUE(MACRO_DARG(Time(971, 254) <= Time(971, 255)));
+ EXPECT_TRUE(MACRO_DARG(Time(971, 254) >= Time(971, 253)));
+ EXPECT_TRUE(MACRO_DARG(Time(971, 254) <= Time(971, 254)));
+ EXPECT_TRUE(MACRO_DARG(Time(971, 254) >= Time(971, 254)));
+ EXPECT_TRUE(MACRO_DARG(Time(972, 254) > Time(971, 254)));
+ EXPECT_TRUE(MACRO_DARG(Time(971, 254) < Time(972, 254)));
+}
+
+TEST(TimeTest, Within) {
+ EXPECT_TRUE(MACRO_DARG(Time(55, 5000).IsWithin(Time(55, 4900), 100)));
+ EXPECT_FALSE(MACRO_DARG(Time(55, 5000).IsWithin(Time(55, 4900), 99)));
+ EXPECT_TRUE(MACRO_DARG(Time(5, 0).IsWithin(Time(4, Time::kNSecInSec - 200),
+ 250)));
+}
+
+TEST(TimeTest, Modulo) {
+ EXPECT_EQ(MACRO_DARG(Time(0, Time::kNSecInSec / 10 * 2)),
+ MACRO_DARG(Time(50, 0) % (Time::kNSecInSec / 10 * 3)));
+}
+
+TEST(TimeTest, InSeconds) {
+ EXPECT_EQ(MACRO_DARG(Time(2, Time::kNSecInSec / 100 * 55 - 1)),
+ Time::InSeconds(2.55));
+}
+
+#ifdef __VXWORKS__
+TEST(TimeTest, ToTicks) {
+ EXPECT_EQ(sysClkRateGet() / 100,
+ MACRO_DARG(Time(0, Time::kNSecInSec / 100).ToTicks()));
+}
+#endif
+
+TEST(TimeTest, InMS) {
+ Time t = Time::InMS(254971);
+ EXPECT_EQ(254, t.sec());
+ EXPECT_EQ(971000000, t.nsec());
+}
+
+TEST(TimeTest, InNS) {
+ Time t = Time::InNS(static_cast<int64_t>(973254111971ll));
+ EXPECT_EQ(973, t.sec());
+ EXPECT_EQ(254111971, t.nsec());
+}
+
+TEST(TimeTest, InUS) {
+ Time t = Time::InUS(254111971);
+ EXPECT_EQ(254, t.sec());
+ EXPECT_EQ(111971000, t.nsec());
+}
+
+TEST(TimeTest, ToMSec) {
+ Time t(254, 971000000);
+ EXPECT_EQ(254971, t.ToMSec());
+}
+
+} // namespace testing
+} // namespace time
+} // namespace aos
diff --git a/aos/common/type_traits.h b/aos/common/type_traits.h
new file mode 100644
index 0000000..9c06b02
--- /dev/null
+++ b/aos/common/type_traits.h
@@ -0,0 +1,38 @@
+#ifndef AOS_COMMON_TYPE_TRAITS_
+#define AOS_COMMON_TYPE_TRAITS_
+
+#ifndef __VXWORKS__
+#include <type_traits>
+#else
+#include "aos/crio/type_traits/type_traits"
+#endif
+
+namespace aos {
+
+// A class template that determines whether or not it is safe to pass a type
+// through the shared memory system (aka whether or not you can memcpy it).
+// Useful in combination with static_assert.
+// Always true when using the cRIO compiler.
+//
+// Doesn't need a trivial constructor because it's bytes only need to get
+// copied, so it does need to not require anything special to be cleaned up
+// (trivial destructor).
+// See also (3.9) [basic.types] in the C++11 standard.
+template<typename Tp>
+struct has_trivial_copy_assign : public std::integral_constant<bool,
+// This changed between 4.4.5 and 4.6.3. Unless somebody discovers otherwise,
+// 4.6 seems like a reasonable place to switch.
+#if ((__GNUC__ < 4) || (__GNUC_MINOR__ < 6)) && !defined(__clang__)
+ std::has_trivial_assign<Tp>::value> {};
+#else
+ std::has_trivial_copy_assign<Tp>::value> {};
+#endif
+template<typename Tp>
+struct shm_ok : public std::integral_constant<bool,
+ (std::has_trivial_copy_constructor<Tp>::value &&
+ aos::has_trivial_copy_assign<Tp>::value &&
+ std::has_trivial_destructor<Tp>::value)> {};
+
+} // namespace aos
+
+#endif
diff --git a/aos/common/type_traits_test.cpp b/aos/common/type_traits_test.cpp
new file mode 100644
index 0000000..aa104ee
--- /dev/null
+++ b/aos/common/type_traits_test.cpp
@@ -0,0 +1,98 @@
+#include "aos/common/type_traits.h"
+
+#include "gtest/gtest.h"
+
+namespace aos {
+namespace testing {
+
+class BadVirtualFunction {
+ virtual void Test() {}
+};
+TEST(TypeTraitsTest, VirtualFunction) {
+ EXPECT_FALSE(shm_ok<BadVirtualFunction>::value);
+}
+class BadPureVirtualFunction {
+ virtual void Test() = 0;
+};
+TEST(TypeTraitsTest, PureVirtualFunction) {
+ EXPECT_FALSE(shm_ok<BadPureVirtualFunction>::value);
+}
+class BadInheritedVirtual : public BadVirtualFunction {};
+TEST(TypeTraitsTest, InheritedVirtualFunction) {
+ EXPECT_FALSE(shm_ok<BadInheritedVirtual>::value);
+}
+class BadVirtualDestructor {
+ virtual ~BadVirtualDestructor();
+};
+TEST(TypeTraitsTest, VirtualDestructor) {
+ EXPECT_FALSE(shm_ok<BadVirtualDestructor>::value);
+}
+class Boring {};
+class BadVirtualBase : public virtual Boring {};
+TEST(TypeTraitsTest, VirtualBase) {
+ EXPECT_FALSE(shm_ok<BadVirtualBase>::value);
+}
+
+class GoodSimple {
+ public:
+ int test1, test2;
+ double test3;
+};
+// Make sure that it lets simple classes through and that the compiler isn't
+// completely nuts.
+TEST(TypeTraitsTest, Basic) {
+ EXPECT_TRUE(shm_ok<GoodSimple>::value);
+ GoodSimple test{5, 4, 34.2};
+ EXPECT_EQ(5, test.test1);
+ EXPECT_EQ(4, test.test2);
+ EXPECT_EQ(34.2, test.test3);
+ memset(&test, 0, sizeof(test));
+ EXPECT_EQ(0, test.test1);
+ EXPECT_EQ(0, test.test2);
+ EXPECT_EQ(0, test.test3);
+}
+
+class GoodWithConstructor {
+ public:
+ int val_;
+ GoodWithConstructor(int val) : val_(val) {}
+};
+// Make sure that it lets classes with constructors through.
+TEST(TypeTraitsTest, GoodWithConstructor) {
+ EXPECT_TRUE(shm_ok<GoodWithConstructor>::value);
+ GoodWithConstructor test(971);
+ EXPECT_EQ(971, test.val_);
+}
+
+class GoodPublicPrivateFunction {
+ public:
+ int32_t a_;
+ void set_a(int32_t a) { a_ = a; }
+ int32_t b() { return b_; }
+ void set_b(int32_t b) { b_ = b; }
+ private:
+ int32_t b_;
+};
+// Make sure that member functions still work.
+TEST(TypeTraitsTest, Function) {
+ EXPECT_TRUE(shm_ok<GoodPublicPrivateFunction>::value);
+ EXPECT_EQ(static_cast<unsigned>(8), sizeof(GoodPublicPrivateFunction)) <<
+ "The compiler did something weird, but it might not be a problem.";
+ GoodPublicPrivateFunction test;
+ test.a_ = 5;
+ test.set_b(971);
+ EXPECT_EQ(5, test.a_);
+ EXPECT_EQ(971, test.b());
+ test.set_a(74);
+ EXPECT_EQ(74, test.a_);
+ memset(&test, 0, sizeof(test));
+ EXPECT_EQ(0, test.a_);
+ EXPECT_EQ(0, test.b());
+ test.set_a(123);
+ test.set_b(254);
+ EXPECT_EQ(123, test.a_);
+ EXPECT_EQ(254, test.b());
+}
+
+} // namespace testing
+} // namespace aos
diff --git a/aos/common/unique_malloc_ptr.h b/aos/common/unique_malloc_ptr.h
new file mode 100644
index 0000000..696b9f3
--- /dev/null
+++ b/aos/common/unique_malloc_ptr.h
@@ -0,0 +1,29 @@
+#include <memory>
+
+namespace aos {
+
+namespace {
+
+template<typename T, void(*function)(T *)>
+void const_wrap(const T *ptr) {
+ function(const_cast<T *>(ptr));
+}
+
+// Wrapper function to deal with the differences between C and C++ (C++ doesn't
+// automatically convert T* to void* like C).
+template<typename T>
+void free_type(T *ptr) { ::free(reinterpret_cast<void *>(ptr)); }
+
+} // namespace
+
+// A std::unique_ptr that should get freed with a C-style free function
+// (free(2) by default).
+template<typename T, void(*function)(T *) = free_type>
+class unique_c_ptr : public std::unique_ptr<T, void(*)(const T *)> {
+ public:
+ unique_c_ptr(T *pointer)
+ : std::unique_ptr<T, void(*)(const T *)>(
+ pointer, const_wrap<T, function>) {}
+};
+
+} // namespace aos
diff --git a/aos/config/README.txt b/aos/config/README.txt
new file mode 100644
index 0000000..8462f69
--- /dev/null
+++ b/aos/config/README.txt
@@ -0,0 +1,11 @@
+[FILES]
+
+fitpc_kernel.config is a kernel configuration file for a fit-pc2
+ it is currently for kernel version 3.2.21
+ directions to use
+ download the 3.2.21 vanilla kernel source and the 3.2.21 rt patch
+ extract the kernel source and apply the patch
+ if on a 64-bit x86 machine, create a 32-bit chroot to build in
+ make sure fakeroot and kernel-package are installed
+ in the linux-x.x.x directory: fakeroot make-kpkg --jobs=4 kernel_image
+
diff --git a/aos/config/aos.conf b/aos/config/aos.conf
new file mode 100644
index 0000000..29d84fa
--- /dev/null
+++ b/aos/config/aos.conf
@@ -0,0 +1,6 @@
+# put this file in /etc/security/limits.d/ to make it work
+# you have to create a group named aos (groupadd aos) and then add anybody you want to it (vim /etc/group)
+
+@aos hard memlock unlimited
+@aos hard rtprio 40
+
diff --git a/aos/config/fitpc_kernel.config b/aos/config/fitpc_kernel.config
new file mode 100644
index 0000000..e4d8700
--- /dev/null
+++ b/aos/config/fitpc_kernel.config
@@ -0,0 +1,3798 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Linux/i386 3.2.21 Kernel Configuration
+#
+# CONFIG_64BIT is not set
+CONFIG_X86_32=y
+# CONFIG_X86_64 is not set
+CONFIG_X86=y
+CONFIG_INSTRUCTION_DECODER=y
+CONFIG_OUTPUT_FORMAT="elf32-i386"
+CONFIG_ARCH_DEFCONFIG="arch/x86/configs/i386_defconfig"
+CONFIG_GENERIC_CMOS_UPDATE=y
+CONFIG_CLOCKSOURCE_WATCHDOG=y
+CONFIG_GENERIC_CLOCKEVENTS=y
+CONFIG_GENERIC_CLOCKEVENTS_BROADCAST=y
+CONFIG_LOCKDEP_SUPPORT=y
+CONFIG_STACKTRACE_SUPPORT=y
+CONFIG_HAVE_LATENCYTOP_SUPPORT=y
+CONFIG_MMU=y
+CONFIG_ZONE_DMA=y
+# CONFIG_NEED_DMA_MAP_STATE is not set
+CONFIG_NEED_SG_DMA_LENGTH=y
+CONFIG_GENERIC_ISA_DMA=y
+CONFIG_GENERIC_IOMAP=y
+CONFIG_GENERIC_BUG=y
+CONFIG_GENERIC_HWEIGHT=y
+CONFIG_GENERIC_GPIO=y
+CONFIG_ARCH_MAY_HAVE_PC_FDC=y
+CONFIG_RWSEM_GENERIC_SPINLOCK=y
+# CONFIG_RWSEM_XCHGADD_ALGORITHM is not set
+CONFIG_ARCH_HAS_CPU_IDLE_WAIT=y
+CONFIG_GENERIC_CALIBRATE_DELAY=y
+# CONFIG_GENERIC_TIME_VSYSCALL is not set
+CONFIG_ARCH_HAS_CPU_RELAX=y
+CONFIG_ARCH_HAS_DEFAULT_IDLE=y
+CONFIG_ARCH_HAS_CACHE_LINE_SIZE=y
+CONFIG_HAVE_SETUP_PER_CPU_AREA=y
+CONFIG_NEED_PER_CPU_EMBED_FIRST_CHUNK=y
+CONFIG_NEED_PER_CPU_PAGE_FIRST_CHUNK=y
+CONFIG_ARCH_HIBERNATION_POSSIBLE=y
+CONFIG_ARCH_SUSPEND_POSSIBLE=y
+# CONFIG_ZONE_DMA32 is not set
+CONFIG_ARCH_POPULATES_NODE_MAP=y
+# CONFIG_AUDIT_ARCH is not set
+CONFIG_ARCH_SUPPORTS_OPTIMIZED_INLINING=y
+CONFIG_ARCH_SUPPORTS_DEBUG_PAGEALLOC=y
+CONFIG_X86_32_SMP=y
+CONFIG_X86_HT=y
+CONFIG_ARCH_HWEIGHT_CFLAGS="-fcall-saved-ecx -fcall-saved-edx"
+CONFIG_KTIME_SCALAR=y
+CONFIG_ARCH_CPU_PROBE_RELEASE=y
+CONFIG_DEFCONFIG_LIST="/lib/modules/$UNAME_RELEASE/.config"
+CONFIG_HAVE_IRQ_WORK=y
+CONFIG_IRQ_WORK=y
+
+#
+# General setup
+#
+CONFIG_EXPERIMENTAL=y
+CONFIG_INIT_ENV_ARG_LIMIT=32
+CONFIG_CROSS_COMPILE=""
+CONFIG_LOCALVERSION=""
+# CONFIG_LOCALVERSION_AUTO is not set
+CONFIG_HAVE_KERNEL_GZIP=y
+CONFIG_HAVE_KERNEL_BZIP2=y
+CONFIG_HAVE_KERNEL_LZMA=y
+CONFIG_HAVE_KERNEL_XZ=y
+CONFIG_HAVE_KERNEL_LZO=y
+CONFIG_KERNEL_GZIP=y
+# CONFIG_KERNEL_BZIP2 is not set
+# CONFIG_KERNEL_LZMA is not set
+# CONFIG_KERNEL_XZ is not set
+# CONFIG_KERNEL_LZO is not set
+CONFIG_DEFAULT_HOSTNAME="(none)"
+CONFIG_SWAP=y
+CONFIG_SYSVIPC=y
+CONFIG_SYSVIPC_SYSCTL=y
+CONFIG_POSIX_MQUEUE=y
+CONFIG_POSIX_MQUEUE_SYSCTL=y
+CONFIG_BSD_PROCESS_ACCT=y
+CONFIG_BSD_PROCESS_ACCT_V3=y
+# CONFIG_FHANDLE is not set
+CONFIG_TASKSTATS=y
+CONFIG_TASK_DELAY_ACCT=y
+CONFIG_TASK_XACCT=y
+CONFIG_TASK_IO_ACCOUNTING=y
+CONFIG_AUDIT=y
+CONFIG_AUDITSYSCALL=y
+CONFIG_AUDIT_WATCH=y
+CONFIG_AUDIT_TREE=y
+CONFIG_HAVE_GENERIC_HARDIRQS=y
+
+#
+# IRQ subsystem
+#
+CONFIG_GENERIC_HARDIRQS=y
+CONFIG_HAVE_SPARSE_IRQ=y
+CONFIG_GENERIC_IRQ_PROBE=y
+CONFIG_GENERIC_IRQ_SHOW=y
+CONFIG_GENERIC_PENDING_IRQ=y
+CONFIG_IRQ_FORCED_THREADING=y
+CONFIG_SPARSE_IRQ=y
+
+#
+# RCU Subsystem
+#
+CONFIG_TREE_PREEMPT_RCU=y
+CONFIG_PREEMPT_RCU=y
+# CONFIG_RCU_TRACE is not set
+CONFIG_RCU_FANOUT=32
+# CONFIG_RCU_FANOUT_EXACT is not set
+# CONFIG_TREE_RCU_TRACE is not set
+# CONFIG_RCU_BOOST is not set
+CONFIG_IKCONFIG=y
+CONFIG_IKCONFIG_PROC=y
+CONFIG_LOG_BUF_SHIFT=17
+CONFIG_HAVE_UNSTABLE_SCHED_CLOCK=y
+CONFIG_CGROUPS=y
+# CONFIG_CGROUP_DEBUG is not set
+CONFIG_CGROUP_FREEZER=y
+CONFIG_CGROUP_DEVICE=y
+CONFIG_CPUSETS=y
+CONFIG_PROC_PID_CPUSET=y
+CONFIG_CGROUP_CPUACCT=y
+# CONFIG_RESOURCE_COUNTERS is not set
+# CONFIG_CGROUP_PERF is not set
+CONFIG_CGROUP_SCHED=y
+CONFIG_FAIR_GROUP_SCHED=y
+# CONFIG_CFS_BANDWIDTH is not set
+# CONFIG_RT_GROUP_SCHED is not set
+# CONFIG_BLK_CGROUP is not set
+CONFIG_NAMESPACES=y
+CONFIG_UTS_NS=y
+CONFIG_IPC_NS=y
+CONFIG_USER_NS=y
+CONFIG_PID_NS=y
+CONFIG_NET_NS=y
+# CONFIG_SCHED_AUTOGROUP is not set
+# CONFIG_SYSFS_DEPRECATED is not set
+CONFIG_RELAY=y
+CONFIG_BLK_DEV_INITRD=y
+CONFIG_INITRAMFS_SOURCE=""
+CONFIG_RD_GZIP=y
+CONFIG_RD_BZIP2=y
+CONFIG_RD_LZMA=y
+CONFIG_RD_XZ=y
+CONFIG_RD_LZO=y
+# CONFIG_CC_OPTIMIZE_FOR_SIZE is not set
+CONFIG_SYSCTL=y
+CONFIG_ANON_INODES=y
+# CONFIG_EXPERT is not set
+CONFIG_UID16=y
+# CONFIG_SYSCTL_SYSCALL is not set
+CONFIG_KALLSYMS=y
+# CONFIG_KALLSYMS_ALL is not set
+CONFIG_HOTPLUG=y
+CONFIG_PRINTK=y
+CONFIG_BUG=y
+CONFIG_ELF_CORE=y
+CONFIG_PCSPKR_PLATFORM=y
+CONFIG_HAVE_PCSPKR_PLATFORM=y
+CONFIG_BASE_FULL=y
+CONFIG_FUTEX=y
+CONFIG_EPOLL=y
+CONFIG_SIGNALFD=y
+CONFIG_TIMERFD=y
+CONFIG_EVENTFD=y
+CONFIG_SHMEM=y
+CONFIG_AIO=y
+# CONFIG_EMBEDDED is not set
+CONFIG_HAVE_PERF_EVENTS=y
+
+#
+# Kernel Performance Events And Counters
+#
+CONFIG_PERF_EVENTS=y
+# CONFIG_PERF_COUNTERS is not set
+# CONFIG_DEBUG_PERF_USE_VMALLOC is not set
+CONFIG_VM_EVENT_COUNTERS=y
+CONFIG_PCI_QUIRKS=y
+# CONFIG_COMPAT_BRK is not set
+CONFIG_SLAB=y
+CONFIG_PROFILING=y
+CONFIG_TRACEPOINTS=y
+CONFIG_HAVE_OPROFILE=y
+CONFIG_KPROBES=y
+# CONFIG_JUMP_LABEL is not set
+CONFIG_HAVE_EFFICIENT_UNALIGNED_ACCESS=y
+CONFIG_KRETPROBES=y
+CONFIG_HAVE_IOREMAP_PROT=y
+CONFIG_HAVE_KPROBES=y
+CONFIG_HAVE_KRETPROBES=y
+CONFIG_HAVE_OPTPROBES=y
+CONFIG_HAVE_ARCH_TRACEHOOK=y
+CONFIG_HAVE_DMA_ATTRS=y
+CONFIG_USE_GENERIC_SMP_HELPERS=y
+CONFIG_HAVE_REGS_AND_STACK_ACCESS_API=y
+CONFIG_HAVE_DMA_API_DEBUG=y
+CONFIG_HAVE_HW_BREAKPOINT=y
+CONFIG_HAVE_MIXED_BREAKPOINTS_REGS=y
+CONFIG_HAVE_USER_RETURN_NOTIFIER=y
+CONFIG_HAVE_PERF_EVENTS_NMI=y
+CONFIG_HAVE_ARCH_JUMP_LABEL=y
+CONFIG_ARCH_HAVE_NMI_SAFE_CMPXCHG=y
+
+#
+# GCOV-based kernel profiling
+#
+# CONFIG_GCOV_KERNEL is not set
+CONFIG_HAVE_GENERIC_DMA_COHERENT=y
+CONFIG_SLABINFO=y
+CONFIG_RT_MUTEXES=y
+CONFIG_BASE_SMALL=0
+CONFIG_MODULES=y
+CONFIG_MODULE_FORCE_LOAD=y
+CONFIG_MODULE_UNLOAD=y
+CONFIG_MODULE_FORCE_UNLOAD=y
+CONFIG_MODVERSIONS=y
+CONFIG_MODULE_SRCVERSION_ALL=y
+CONFIG_STOP_MACHINE=y
+CONFIG_BLOCK=y
+CONFIG_LBDAF=y
+CONFIG_BLK_DEV_BSG=y
+CONFIG_BLK_DEV_BSGLIB=y
+CONFIG_BLK_DEV_INTEGRITY=y
+
+#
+# IO Schedulers
+#
+CONFIG_IOSCHED_NOOP=y
+CONFIG_IOSCHED_DEADLINE=y
+CONFIG_IOSCHED_CFQ=y
+CONFIG_DEFAULT_DEADLINE=y
+# CONFIG_DEFAULT_CFQ is not set
+# CONFIG_DEFAULT_NOOP is not set
+CONFIG_DEFAULT_IOSCHED="deadline"
+# CONFIG_INLINE_SPIN_TRYLOCK is not set
+# CONFIG_INLINE_SPIN_TRYLOCK_BH is not set
+# CONFIG_INLINE_SPIN_LOCK is not set
+# CONFIG_INLINE_SPIN_LOCK_BH is not set
+# CONFIG_INLINE_SPIN_LOCK_IRQ is not set
+# CONFIG_INLINE_SPIN_LOCK_IRQSAVE is not set
+# CONFIG_INLINE_SPIN_UNLOCK is not set
+# CONFIG_INLINE_SPIN_UNLOCK_BH is not set
+# CONFIG_INLINE_SPIN_UNLOCK_IRQ is not set
+# CONFIG_INLINE_SPIN_UNLOCK_IRQRESTORE is not set
+# CONFIG_INLINE_READ_TRYLOCK is not set
+# CONFIG_INLINE_READ_LOCK is not set
+# CONFIG_INLINE_READ_LOCK_BH is not set
+# CONFIG_INLINE_READ_LOCK_IRQ is not set
+# CONFIG_INLINE_READ_LOCK_IRQSAVE is not set
+# CONFIG_INLINE_READ_UNLOCK is not set
+# CONFIG_INLINE_READ_UNLOCK_BH is not set
+# CONFIG_INLINE_READ_UNLOCK_IRQ is not set
+# CONFIG_INLINE_READ_UNLOCK_IRQRESTORE is not set
+# CONFIG_INLINE_WRITE_TRYLOCK is not set
+# CONFIG_INLINE_WRITE_LOCK is not set
+# CONFIG_INLINE_WRITE_LOCK_BH is not set
+# CONFIG_INLINE_WRITE_LOCK_IRQ is not set
+# CONFIG_INLINE_WRITE_LOCK_IRQSAVE is not set
+# CONFIG_INLINE_WRITE_UNLOCK is not set
+# CONFIG_INLINE_WRITE_UNLOCK_BH is not set
+# CONFIG_INLINE_WRITE_UNLOCK_IRQ is not set
+# CONFIG_INLINE_WRITE_UNLOCK_IRQRESTORE is not set
+# CONFIG_MUTEX_SPIN_ON_OWNER is not set
+CONFIG_FREEZER=y
+
+#
+# Processor type and features
+#
+CONFIG_TICK_ONESHOT=y
+CONFIG_NO_HZ=y
+CONFIG_HIGH_RES_TIMERS=y
+CONFIG_GENERIC_CLOCKEVENTS_BUILD=y
+CONFIG_GENERIC_CLOCKEVENTS_MIN_ADJUST=y
+CONFIG_SMP=y
+# CONFIG_X86_MPPARSE is not set
+# CONFIG_X86_BIGSMP is not set
+# CONFIG_X86_EXTENDED_PLATFORM is not set
+# CONFIG_X86_32_IRIS is not set
+CONFIG_SCHED_OMIT_FRAME_POINTER=y
+# CONFIG_PARAVIRT_GUEST is not set
+CONFIG_NO_BOOTMEM=y
+# CONFIG_MEMTEST is not set
+# CONFIG_M386 is not set
+# CONFIG_M486 is not set
+# CONFIG_M586 is not set
+# CONFIG_M586TSC is not set
+# CONFIG_M586MMX is not set
+# CONFIG_M686 is not set
+# CONFIG_MPENTIUMII is not set
+# CONFIG_MPENTIUMIII is not set
+# CONFIG_MPENTIUMM is not set
+# CONFIG_MPENTIUM4 is not set
+# CONFIG_MK6 is not set
+# CONFIG_MK7 is not set
+# CONFIG_MK8 is not set
+# CONFIG_MCRUSOE is not set
+# CONFIG_MEFFICEON is not set
+# CONFIG_MWINCHIPC6 is not set
+# CONFIG_MWINCHIP3D is not set
+# CONFIG_MELAN is not set
+# CONFIG_MGEODEGX1 is not set
+# CONFIG_MGEODE_LX is not set
+# CONFIG_MCYRIXIII is not set
+# CONFIG_MVIAC3_2 is not set
+# CONFIG_MVIAC7 is not set
+# CONFIG_MCORE2 is not set
+CONFIG_MATOM=y
+# CONFIG_X86_GENERIC is not set
+CONFIG_X86_INTERNODE_CACHE_SHIFT=6
+CONFIG_X86_CMPXCHG=y
+CONFIG_CMPXCHG_LOCAL=y
+CONFIG_CMPXCHG_DOUBLE=y
+CONFIG_X86_L1_CACHE_SHIFT=6
+CONFIG_X86_XADD=y
+CONFIG_X86_WP_WORKS_OK=y
+CONFIG_X86_INVLPG=y
+CONFIG_X86_BSWAP=y
+CONFIG_X86_POPAD_OK=y
+CONFIG_X86_USE_PPRO_CHECKSUM=y
+CONFIG_X86_TSC=y
+CONFIG_X86_CMPXCHG64=y
+CONFIG_X86_CMOV=y
+CONFIG_X86_MINIMUM_CPU_FAMILY=5
+CONFIG_X86_DEBUGCTLMSR=y
+CONFIG_CPU_SUP_INTEL=y
+CONFIG_CPU_SUP_CYRIX_32=y
+CONFIG_CPU_SUP_AMD=y
+CONFIG_CPU_SUP_CENTAUR=y
+CONFIG_CPU_SUP_TRANSMETA_32=y
+CONFIG_CPU_SUP_UMC_32=y
+CONFIG_HPET_TIMER=y
+CONFIG_HPET_EMULATE_RTC=y
+CONFIG_DMI=y
+# CONFIG_IOMMU_HELPER is not set
+CONFIG_NR_CPUS=8
+CONFIG_SCHED_SMT=y
+CONFIG_SCHED_MC=y
+# CONFIG_IRQ_TIME_ACCOUNTING is not set
+CONFIG_PREEMPT=y
+CONFIG_PREEMPT_RT_BASE=y
+# CONFIG_PREEMPT_NONE is not set
+# CONFIG_PREEMPT_VOLUNTARY is not set
+# CONFIG_PREEMPT__LL is not set
+# CONFIG_PREEMPT_RTB is not set
+CONFIG_PREEMPT_RT_FULL=y
+CONFIG_PREEMPT_COUNT=y
+CONFIG_X86_LOCAL_APIC=y
+CONFIG_X86_IO_APIC=y
+CONFIG_X86_REROUTE_FOR_BROKEN_BOOT_IRQS=y
+CONFIG_X86_MCE=y
+CONFIG_X86_MCE_INTEL=y
+# CONFIG_X86_MCE_AMD is not set
+# CONFIG_X86_ANCIENT_MCE is not set
+CONFIG_X86_MCE_THRESHOLD=y
+# CONFIG_X86_MCE_INJECT is not set
+CONFIG_X86_THERMAL_VECTOR=y
+CONFIG_VM86=y
+# CONFIG_TOSHIBA is not set
+# CONFIG_I8K is not set
+# CONFIG_X86_REBOOTFIXUPS is not set
+CONFIG_MICROCODE=m
+CONFIG_MICROCODE_INTEL=y
+# CONFIG_MICROCODE_AMD is not set
+CONFIG_MICROCODE_OLD_INTERFACE=y
+CONFIG_X86_MSR=m
+CONFIG_X86_CPUID=m
+# CONFIG_NOHIGHMEM is not set
+CONFIG_HIGHMEM4G=y
+# CONFIG_HIGHMEM64G is not set
+CONFIG_PAGE_OFFSET=0xC0000000
+CONFIG_HIGHMEM=y
+# CONFIG_ARCH_PHYS_ADDR_T_64BIT is not set
+# CONFIG_ARCH_DMA_ADDR_T_64BIT is not set
+CONFIG_NEED_NODE_MEMMAP_SIZE=y
+CONFIG_ARCH_FLATMEM_ENABLE=y
+CONFIG_ARCH_SPARSEMEM_ENABLE=y
+CONFIG_ARCH_SELECT_MEMORY_MODEL=y
+CONFIG_ILLEGAL_POINTER_VALUE=0
+CONFIG_SELECT_MEMORY_MODEL=y
+# CONFIG_FLATMEM_MANUAL is not set
+CONFIG_SPARSEMEM_MANUAL=y
+CONFIG_SPARSEMEM=y
+CONFIG_HAVE_MEMORY_PRESENT=y
+CONFIG_SPARSEMEM_STATIC=y
+CONFIG_HAVE_MEMBLOCK=y
+# CONFIG_MEMORY_HOTPLUG is not set
+CONFIG_SPLIT_PTLOCK_CPUS=4
+# CONFIG_COMPACTION is not set
+# CONFIG_PHYS_ADDR_T_64BIT is not set
+CONFIG_ZONE_DMA_FLAG=1
+CONFIG_BOUNCE=y
+CONFIG_VIRT_TO_BUS=y
+# CONFIG_KSM is not set
+CONFIG_DEFAULT_MMAP_MIN_ADDR=65536
+# CONFIG_CLEANCACHE is not set
+# CONFIG_HIGHPTE is not set
+# CONFIG_X86_CHECK_BIOS_CORRUPTION is not set
+CONFIG_X86_RESERVE_LOW=64
+# CONFIG_MATH_EMULATION is not set
+CONFIG_MTRR=y
+CONFIG_MTRR_SANITIZER=y
+CONFIG_MTRR_SANITIZER_ENABLE_DEFAULT=0
+CONFIG_MTRR_SANITIZER_SPARE_REG_NR_DEFAULT=1
+CONFIG_X86_PAT=y
+CONFIG_ARCH_USES_PG_UNCACHED=y
+CONFIG_ARCH_RANDOM=y
+# CONFIG_EFI is not set
+# CONFIG_SECCOMP is not set
+CONFIG_CC_STACKPROTECTOR=y
+# CONFIG_HZ_100 is not set
+# CONFIG_HZ_250 is not set
+# CONFIG_HZ_300 is not set
+CONFIG_HZ_1000=y
+CONFIG_HZ=1000
+CONFIG_SCHED_HRTICK=y
+CONFIG_KEXEC=y
+# CONFIG_CRASH_DUMP is not set
+CONFIG_PHYSICAL_START=0x1000000
+CONFIG_RELOCATABLE=y
+CONFIG_X86_NEED_RELOCS=y
+CONFIG_PHYSICAL_ALIGN=0x1000000
+CONFIG_HOTPLUG_CPU=y
+CONFIG_COMPAT_VDSO=y
+# CONFIG_CMDLINE_BOOL is not set
+CONFIG_ARCH_ENABLE_MEMORY_HOTPLUG=y
+
+#
+# Power management and ACPI options
+#
+# CONFIG_SUSPEND is not set
+# CONFIG_HIBERNATION is not set
+CONFIG_PM_RUNTIME=y
+CONFIG_PM=y
+CONFIG_PM_DEBUG=y
+# CONFIG_PM_ADVANCED_DEBUG is not set
+CONFIG_ACPI=y
+CONFIG_ACPI_PROCFS=y
+# CONFIG_ACPI_PROCFS_POWER is not set
+# CONFIG_ACPI_EC_DEBUGFS is not set
+# CONFIG_ACPI_PROC_EVENT is not set
+CONFIG_ACPI_AC=y
+CONFIG_ACPI_BATTERY=y
+CONFIG_ACPI_BUTTON=y
+CONFIG_ACPI_VIDEO=y
+# CONFIG_ACPI_FAN is not set
+CONFIG_ACPI_DOCK=y
+CONFIG_ACPI_PROCESSOR=y
+# CONFIG_ACPI_IPMI is not set
+CONFIG_ACPI_HOTPLUG_CPU=y
+CONFIG_ACPI_PROCESSOR_AGGREGATOR=m
+CONFIG_ACPI_THERMAL=y
+# CONFIG_ACPI_CUSTOM_DSDT is not set
+CONFIG_ACPI_BLACKLIST_YEAR=0
+# CONFIG_ACPI_DEBUG is not set
+CONFIG_ACPI_PCI_SLOT=m
+CONFIG_X86_PM_TIMER=y
+CONFIG_ACPI_CONTAINER=y
+CONFIG_ACPI_SBS=m
+# CONFIG_ACPI_HED is not set
+# CONFIG_ACPI_CUSTOM_METHOD is not set
+# CONFIG_ACPI_APEI is not set
+CONFIG_SFI=y
+
+#
+# CPU Frequency scaling
+#
+CONFIG_CPU_FREQ=y
+CONFIG_CPU_FREQ_TABLE=y
+CONFIG_CPU_FREQ_STAT=m
+# CONFIG_CPU_FREQ_STAT_DETAILS is not set
+CONFIG_CPU_FREQ_DEFAULT_GOV_PERFORMANCE=y
+# CONFIG_CPU_FREQ_DEFAULT_GOV_USERSPACE is not set
+# CONFIG_CPU_FREQ_DEFAULT_GOV_ONDEMAND is not set
+# CONFIG_CPU_FREQ_DEFAULT_GOV_CONSERVATIVE is not set
+CONFIG_CPU_FREQ_GOV_PERFORMANCE=y
+# CONFIG_CPU_FREQ_GOV_POWERSAVE is not set
+# CONFIG_CPU_FREQ_GOV_USERSPACE is not set
+CONFIG_CPU_FREQ_GOV_ONDEMAND=y
+# CONFIG_CPU_FREQ_GOV_CONSERVATIVE is not set
+
+#
+# x86 CPU frequency scaling drivers
+#
+# CONFIG_X86_PCC_CPUFREQ is not set
+CONFIG_X86_ACPI_CPUFREQ=m
+# CONFIG_X86_POWERNOW_K6 is not set
+# CONFIG_X86_POWERNOW_K7 is not set
+# CONFIG_X86_POWERNOW_K8 is not set
+# CONFIG_X86_GX_SUSPMOD is not set
+CONFIG_X86_SPEEDSTEP_CENTRINO=m
+CONFIG_X86_SPEEDSTEP_CENTRINO_TABLE=y
+# CONFIG_X86_SPEEDSTEP_ICH is not set
+# CONFIG_X86_SPEEDSTEP_SMI is not set
+# CONFIG_X86_P4_CLOCKMOD is not set
+# CONFIG_X86_CPUFREQ_NFORCE2 is not set
+# CONFIG_X86_LONGRUN is not set
+# CONFIG_X86_LONGHAUL is not set
+# CONFIG_X86_E_POWERSAVER is not set
+
+#
+# shared options
+#
+# CONFIG_X86_SPEEDSTEP_LIB is not set
+CONFIG_CPU_IDLE=y
+CONFIG_CPU_IDLE_GOV_LADDER=y
+CONFIG_CPU_IDLE_GOV_MENU=y
+CONFIG_INTEL_IDLE=y
+
+#
+# Bus options (PCI etc.)
+#
+CONFIG_PCI=y
+# CONFIG_PCI_GOBIOS is not set
+# CONFIG_PCI_GOMMCONFIG is not set
+# CONFIG_PCI_GODIRECT is not set
+CONFIG_PCI_GOANY=y
+CONFIG_PCI_BIOS=y
+CONFIG_PCI_DIRECT=y
+CONFIG_PCI_MMCONFIG=y
+CONFIG_PCI_DOMAINS=y
+# CONFIG_PCI_CNB20LE_QUIRK is not set
+CONFIG_PCIEPORTBUS=y
+# CONFIG_HOTPLUG_PCI_PCIE is not set
+CONFIG_PCIEAER=y
+# CONFIG_PCIE_ECRC is not set
+# CONFIG_PCIEAER_INJECT is not set
+CONFIG_PCIEASPM=y
+# CONFIG_PCIEASPM_DEBUG is not set
+CONFIG_PCIE_PME=y
+CONFIG_ARCH_SUPPORTS_MSI=y
+CONFIG_PCI_MSI=y
+# CONFIG_PCI_DEBUG is not set
+# CONFIG_PCI_STUB is not set
+CONFIG_HT_IRQ=y
+CONFIG_PCI_ATS=y
+CONFIG_PCI_IOV=y
+# CONFIG_PCI_PRI is not set
+# CONFIG_PCI_PASID is not set
+CONFIG_PCI_IOAPIC=y
+CONFIG_PCI_LABEL=y
+CONFIG_ISA_DMA_API=y
+# CONFIG_ISA is not set
+# CONFIG_MCA is not set
+# CONFIG_SCx200 is not set
+# CONFIG_OLPC is not set
+# CONFIG_ALIX is not set
+CONFIG_AMD_NB=y
+# CONFIG_PCCARD is not set
+CONFIG_HOTPLUG_PCI=m
+CONFIG_HOTPLUG_PCI_FAKE=m
+# CONFIG_HOTPLUG_PCI_COMPAQ is not set
+# CONFIG_HOTPLUG_PCI_IBM is not set
+CONFIG_HOTPLUG_PCI_ACPI=m
+CONFIG_HOTPLUG_PCI_ACPI_IBM=m
+CONFIG_HOTPLUG_PCI_CPCI=y
+CONFIG_HOTPLUG_PCI_CPCI_ZT5550=m
+CONFIG_HOTPLUG_PCI_CPCI_GENERIC=m
+CONFIG_HOTPLUG_PCI_SHPC=m
+# CONFIG_RAPIDIO is not set
+
+#
+# Executable file formats / Emulations
+#
+CONFIG_BINFMT_ELF=y
+CONFIG_CORE_DUMP_DEFAULT_ELF_HEADERS=y
+CONFIG_HAVE_AOUT=y
+# CONFIG_BINFMT_AOUT is not set
+CONFIG_BINFMT_MISC=m
+CONFIG_HAVE_ATOMIC_IOMAP=y
+CONFIG_HAVE_TEXT_POKE_SMP=y
+CONFIG_NET=y
+
+#
+# Networking options
+#
+CONFIG_PACKET=y
+CONFIG_UNIX=y
+CONFIG_XFRM=y
+CONFIG_XFRM_USER=m
+CONFIG_XFRM_SUB_POLICY=y
+CONFIG_XFRM_MIGRATE=y
+# CONFIG_XFRM_STATISTICS is not set
+CONFIG_XFRM_IPCOMP=m
+CONFIG_NET_KEY=m
+CONFIG_NET_KEY_MIGRATE=y
+CONFIG_INET=y
+CONFIG_IP_MULTICAST=y
+CONFIG_IP_ADVANCED_ROUTER=y
+# CONFIG_IP_FIB_TRIE_STATS is not set
+CONFIG_IP_MULTIPLE_TABLES=y
+CONFIG_IP_ROUTE_MULTIPATH=y
+CONFIG_IP_ROUTE_VERBOSE=y
+CONFIG_IP_ROUTE_CLASSID=y
+# CONFIG_IP_PNP is not set
+CONFIG_NET_IPIP=m
+# CONFIG_NET_IPGRE_DEMUX is not set
+CONFIG_IP_MROUTE=y
+# CONFIG_IP_MROUTE_MULTIPLE_TABLES is not set
+CONFIG_IP_PIMSM_V1=y
+CONFIG_IP_PIMSM_V2=y
+# CONFIG_ARPD is not set
+CONFIG_SYN_COOKIES=y
+CONFIG_INET_AH=m
+CONFIG_INET_ESP=m
+CONFIG_INET_IPCOMP=m
+CONFIG_INET_XFRM_TUNNEL=m
+CONFIG_INET_TUNNEL=m
+CONFIG_INET_XFRM_MODE_TRANSPORT=m
+CONFIG_INET_XFRM_MODE_TUNNEL=m
+CONFIG_INET_XFRM_MODE_BEET=m
+CONFIG_INET_LRO=m
+CONFIG_INET_DIAG=m
+CONFIG_INET_TCP_DIAG=m
+CONFIG_TCP_CONG_ADVANCED=y
+CONFIG_TCP_CONG_BIC=m
+CONFIG_TCP_CONG_CUBIC=y
+CONFIG_TCP_CONG_WESTWOOD=m
+CONFIG_TCP_CONG_HTCP=m
+CONFIG_TCP_CONG_HSTCP=m
+CONFIG_TCP_CONG_HYBLA=m
+CONFIG_TCP_CONG_VEGAS=m
+CONFIG_TCP_CONG_SCALABLE=m
+CONFIG_TCP_CONG_LP=m
+CONFIG_TCP_CONG_VENO=m
+CONFIG_TCP_CONG_YEAH=m
+CONFIG_TCP_CONG_ILLINOIS=m
+CONFIG_DEFAULT_CUBIC=y
+# CONFIG_DEFAULT_RENO is not set
+CONFIG_DEFAULT_TCP_CONG="cubic"
+CONFIG_TCP_MD5SIG=y
+CONFIG_IPV6=y
+CONFIG_IPV6_PRIVACY=y
+CONFIG_IPV6_ROUTER_PREF=y
+CONFIG_IPV6_ROUTE_INFO=y
+CONFIG_IPV6_OPTIMISTIC_DAD=y
+CONFIG_INET6_AH=m
+CONFIG_INET6_ESP=m
+CONFIG_INET6_IPCOMP=m
+CONFIG_IPV6_MIP6=y
+CONFIG_INET6_XFRM_TUNNEL=m
+CONFIG_INET6_TUNNEL=m
+CONFIG_INET6_XFRM_MODE_TRANSPORT=m
+CONFIG_INET6_XFRM_MODE_TUNNEL=m
+CONFIG_INET6_XFRM_MODE_BEET=m
+CONFIG_INET6_XFRM_MODE_ROUTEOPTIMIZATION=m
+CONFIG_IPV6_SIT=m
+# CONFIG_IPV6_SIT_6RD is not set
+CONFIG_IPV6_NDISC_NODETYPE=y
+CONFIG_IPV6_TUNNEL=m
+CONFIG_IPV6_MULTIPLE_TABLES=y
+CONFIG_IPV6_SUBTREES=y
+CONFIG_IPV6_MROUTE=y
+# CONFIG_IPV6_MROUTE_MULTIPLE_TABLES is not set
+CONFIG_IPV6_PIMSM_V2=y
+# CONFIG_NETLABEL is not set
+CONFIG_NETWORK_SECMARK=y
+# CONFIG_NETWORK_PHY_TIMESTAMPING is not set
+CONFIG_NETFILTER=y
+# CONFIG_NETFILTER_DEBUG is not set
+CONFIG_NETFILTER_ADVANCED=y
+CONFIG_BRIDGE_NETFILTER=y
+
+#
+# Core Netfilter Configuration
+#
+CONFIG_NETFILTER_NETLINK=m
+CONFIG_NETFILTER_NETLINK_QUEUE=m
+CONFIG_NETFILTER_NETLINK_LOG=m
+CONFIG_NF_CONNTRACK=m
+CONFIG_NF_CONNTRACK_MARK=y
+CONFIG_NF_CONNTRACK_SECMARK=y
+CONFIG_NF_CONNTRACK_EVENTS=y
+# CONFIG_NF_CONNTRACK_TIMESTAMP is not set
+CONFIG_NF_CT_PROTO_DCCP=m
+CONFIG_NF_CT_PROTO_GRE=m
+CONFIG_NF_CT_PROTO_SCTP=m
+CONFIG_NF_CT_PROTO_UDPLITE=m
+CONFIG_NF_CONNTRACK_AMANDA=m
+CONFIG_NF_CONNTRACK_FTP=m
+CONFIG_NF_CONNTRACK_H323=m
+CONFIG_NF_CONNTRACK_IRC=m
+CONFIG_NF_CONNTRACK_BROADCAST=m
+CONFIG_NF_CONNTRACK_NETBIOS_NS=m
+# CONFIG_NF_CONNTRACK_SNMP is not set
+CONFIG_NF_CONNTRACK_PPTP=m
+CONFIG_NF_CONNTRACK_SANE=m
+CONFIG_NF_CONNTRACK_SIP=m
+CONFIG_NF_CONNTRACK_TFTP=m
+CONFIG_NF_CT_NETLINK=m
+CONFIG_NETFILTER_TPROXY=m
+CONFIG_NETFILTER_XTABLES=m
+
+#
+# Xtables combined modules
+#
+CONFIG_NETFILTER_XT_MARK=m
+CONFIG_NETFILTER_XT_CONNMARK=m
+
+#
+# Xtables targets
+#
+# CONFIG_NETFILTER_XT_TARGET_AUDIT is not set
+# CONFIG_NETFILTER_XT_TARGET_CHECKSUM is not set
+CONFIG_NETFILTER_XT_TARGET_CLASSIFY=m
+CONFIG_NETFILTER_XT_TARGET_CONNMARK=m
+CONFIG_NETFILTER_XT_TARGET_CONNSECMARK=m
+# CONFIG_NETFILTER_XT_TARGET_CT is not set
+CONFIG_NETFILTER_XT_TARGET_DSCP=m
+CONFIG_NETFILTER_XT_TARGET_HL=m
+# CONFIG_NETFILTER_XT_TARGET_IDLETIMER is not set
+CONFIG_NETFILTER_XT_TARGET_LED=m
+CONFIG_NETFILTER_XT_TARGET_MARK=m
+CONFIG_NETFILTER_XT_TARGET_NFLOG=m
+CONFIG_NETFILTER_XT_TARGET_NFQUEUE=m
+CONFIG_NETFILTER_XT_TARGET_NOTRACK=m
+CONFIG_NETFILTER_XT_TARGET_RATEEST=m
+# CONFIG_NETFILTER_XT_TARGET_TEE is not set
+CONFIG_NETFILTER_XT_TARGET_TPROXY=m
+CONFIG_NETFILTER_XT_TARGET_TRACE=m
+CONFIG_NETFILTER_XT_TARGET_SECMARK=m
+CONFIG_NETFILTER_XT_TARGET_TCPMSS=m
+CONFIG_NETFILTER_XT_TARGET_TCPOPTSTRIP=m
+
+#
+# Xtables matches
+#
+# CONFIG_NETFILTER_XT_MATCH_ADDRTYPE is not set
+CONFIG_NETFILTER_XT_MATCH_CLUSTER=m
+CONFIG_NETFILTER_XT_MATCH_COMMENT=m
+CONFIG_NETFILTER_XT_MATCH_CONNBYTES=m
+CONFIG_NETFILTER_XT_MATCH_CONNLIMIT=m
+CONFIG_NETFILTER_XT_MATCH_CONNMARK=m
+CONFIG_NETFILTER_XT_MATCH_CONNTRACK=m
+# CONFIG_NETFILTER_XT_MATCH_CPU is not set
+CONFIG_NETFILTER_XT_MATCH_DCCP=m
+# CONFIG_NETFILTER_XT_MATCH_DEVGROUP is not set
+CONFIG_NETFILTER_XT_MATCH_DSCP=m
+CONFIG_NETFILTER_XT_MATCH_ESP=m
+CONFIG_NETFILTER_XT_MATCH_HASHLIMIT=m
+CONFIG_NETFILTER_XT_MATCH_HELPER=m
+CONFIG_NETFILTER_XT_MATCH_HL=m
+CONFIG_NETFILTER_XT_MATCH_IPRANGE=m
+# CONFIG_NETFILTER_XT_MATCH_IPVS is not set
+CONFIG_NETFILTER_XT_MATCH_LENGTH=m
+CONFIG_NETFILTER_XT_MATCH_LIMIT=m
+CONFIG_NETFILTER_XT_MATCH_MAC=m
+CONFIG_NETFILTER_XT_MATCH_MARK=m
+CONFIG_NETFILTER_XT_MATCH_MULTIPORT=m
+CONFIG_NETFILTER_XT_MATCH_OSF=m
+CONFIG_NETFILTER_XT_MATCH_OWNER=m
+CONFIG_NETFILTER_XT_MATCH_POLICY=m
+CONFIG_NETFILTER_XT_MATCH_PHYSDEV=m
+CONFIG_NETFILTER_XT_MATCH_PKTTYPE=m
+CONFIG_NETFILTER_XT_MATCH_QUOTA=m
+CONFIG_NETFILTER_XT_MATCH_RATEEST=m
+CONFIG_NETFILTER_XT_MATCH_REALM=m
+CONFIG_NETFILTER_XT_MATCH_RECENT=m
+CONFIG_NETFILTER_XT_MATCH_SCTP=m
+CONFIG_NETFILTER_XT_MATCH_SOCKET=m
+CONFIG_NETFILTER_XT_MATCH_STATE=m
+CONFIG_NETFILTER_XT_MATCH_STATISTIC=m
+CONFIG_NETFILTER_XT_MATCH_STRING=m
+CONFIG_NETFILTER_XT_MATCH_TCPMSS=m
+CONFIG_NETFILTER_XT_MATCH_TIME=m
+CONFIG_NETFILTER_XT_MATCH_U32=m
+# CONFIG_IP_SET is not set
+CONFIG_IP_VS=m
+CONFIG_IP_VS_IPV6=y
+# CONFIG_IP_VS_DEBUG is not set
+CONFIG_IP_VS_TAB_BITS=12
+
+#
+# IPVS transport protocol load balancing support
+#
+CONFIG_IP_VS_PROTO_TCP=y
+CONFIG_IP_VS_PROTO_UDP=y
+CONFIG_IP_VS_PROTO_AH_ESP=y
+CONFIG_IP_VS_PROTO_ESP=y
+CONFIG_IP_VS_PROTO_AH=y
+# CONFIG_IP_VS_PROTO_SCTP is not set
+
+#
+# IPVS scheduler
+#
+CONFIG_IP_VS_RR=m
+CONFIG_IP_VS_WRR=m
+CONFIG_IP_VS_LC=m
+CONFIG_IP_VS_WLC=m
+CONFIG_IP_VS_LBLC=m
+CONFIG_IP_VS_LBLCR=m
+CONFIG_IP_VS_DH=m
+CONFIG_IP_VS_SH=m
+CONFIG_IP_VS_SED=m
+CONFIG_IP_VS_NQ=m
+
+#
+# IPVS application helper
+#
+CONFIG_IP_VS_FTP=m
+CONFIG_IP_VS_NFCT=y
+# CONFIG_IP_VS_PE_SIP is not set
+
+#
+# IP: Netfilter Configuration
+#
+CONFIG_NF_DEFRAG_IPV4=m
+CONFIG_NF_CONNTRACK_IPV4=m
+CONFIG_NF_CONNTRACK_PROC_COMPAT=y
+CONFIG_IP_NF_QUEUE=m
+CONFIG_IP_NF_IPTABLES=m
+CONFIG_IP_NF_MATCH_AH=m
+CONFIG_IP_NF_MATCH_ECN=m
+CONFIG_IP_NF_MATCH_TTL=m
+CONFIG_IP_NF_FILTER=m
+CONFIG_IP_NF_TARGET_REJECT=m
+CONFIG_IP_NF_TARGET_LOG=m
+CONFIG_IP_NF_TARGET_ULOG=m
+CONFIG_NF_NAT=m
+CONFIG_NF_NAT_NEEDED=y
+CONFIG_IP_NF_TARGET_MASQUERADE=m
+CONFIG_IP_NF_TARGET_NETMAP=m
+CONFIG_IP_NF_TARGET_REDIRECT=m
+CONFIG_NF_NAT_PROTO_DCCP=m
+CONFIG_NF_NAT_PROTO_GRE=m
+CONFIG_NF_NAT_PROTO_UDPLITE=m
+CONFIG_NF_NAT_PROTO_SCTP=m
+CONFIG_NF_NAT_FTP=m
+CONFIG_NF_NAT_IRC=m
+CONFIG_NF_NAT_TFTP=m
+CONFIG_NF_NAT_AMANDA=m
+CONFIG_NF_NAT_PPTP=m
+CONFIG_NF_NAT_H323=m
+CONFIG_NF_NAT_SIP=m
+CONFIG_IP_NF_MANGLE=m
+CONFIG_IP_NF_TARGET_CLUSTERIP=m
+CONFIG_IP_NF_TARGET_ECN=m
+CONFIG_IP_NF_TARGET_TTL=m
+CONFIG_IP_NF_RAW=m
+CONFIG_IP_NF_SECURITY=m
+CONFIG_IP_NF_ARPTABLES=m
+CONFIG_IP_NF_ARPFILTER=m
+CONFIG_IP_NF_ARP_MANGLE=m
+
+#
+# IPv6: Netfilter Configuration
+#
+CONFIG_NF_DEFRAG_IPV6=m
+CONFIG_NF_CONNTRACK_IPV6=m
+CONFIG_IP6_NF_QUEUE=m
+CONFIG_IP6_NF_IPTABLES=m
+CONFIG_IP6_NF_MATCH_AH=m
+CONFIG_IP6_NF_MATCH_EUI64=m
+CONFIG_IP6_NF_MATCH_FRAG=m
+CONFIG_IP6_NF_MATCH_OPTS=m
+CONFIG_IP6_NF_MATCH_HL=m
+CONFIG_IP6_NF_MATCH_IPV6HEADER=m
+CONFIG_IP6_NF_MATCH_MH=m
+CONFIG_IP6_NF_MATCH_RT=m
+CONFIG_IP6_NF_TARGET_HL=m
+CONFIG_IP6_NF_TARGET_LOG=m
+CONFIG_IP6_NF_FILTER=m
+CONFIG_IP6_NF_TARGET_REJECT=m
+CONFIG_IP6_NF_MANGLE=m
+CONFIG_IP6_NF_RAW=m
+CONFIG_IP6_NF_SECURITY=m
+
+#
+# DECnet: Netfilter Configuration
+#
+CONFIG_DECNET_NF_GRABULATOR=m
+CONFIG_BRIDGE_NF_EBTABLES=m
+CONFIG_BRIDGE_EBT_BROUTE=m
+CONFIG_BRIDGE_EBT_T_FILTER=m
+CONFIG_BRIDGE_EBT_T_NAT=m
+CONFIG_BRIDGE_EBT_802_3=m
+CONFIG_BRIDGE_EBT_AMONG=m
+CONFIG_BRIDGE_EBT_ARP=m
+CONFIG_BRIDGE_EBT_IP=m
+CONFIG_BRIDGE_EBT_IP6=m
+CONFIG_BRIDGE_EBT_LIMIT=m
+CONFIG_BRIDGE_EBT_MARK=m
+CONFIG_BRIDGE_EBT_PKTTYPE=m
+CONFIG_BRIDGE_EBT_STP=m
+CONFIG_BRIDGE_EBT_VLAN=m
+CONFIG_BRIDGE_EBT_ARPREPLY=m
+CONFIG_BRIDGE_EBT_DNAT=m
+CONFIG_BRIDGE_EBT_MARK_T=m
+CONFIG_BRIDGE_EBT_REDIRECT=m
+CONFIG_BRIDGE_EBT_SNAT=m
+CONFIG_BRIDGE_EBT_LOG=m
+CONFIG_BRIDGE_EBT_ULOG=m
+CONFIG_BRIDGE_EBT_NFLOG=m
+CONFIG_IP_DCCP=m
+CONFIG_INET_DCCP_DIAG=m
+
+#
+# DCCP CCIDs Configuration (EXPERIMENTAL)
+#
+# CONFIG_IP_DCCP_CCID2_DEBUG is not set
+CONFIG_IP_DCCP_CCID3=y
+# CONFIG_IP_DCCP_CCID3_DEBUG is not set
+CONFIG_IP_DCCP_TFRC_LIB=y
+
+#
+# DCCP Kernel Hacking
+#
+# CONFIG_IP_DCCP_DEBUG is not set
+# CONFIG_NET_DCCPPROBE is not set
+CONFIG_IP_SCTP=m
+# CONFIG_NET_SCTPPROBE is not set
+# CONFIG_SCTP_DBG_MSG is not set
+# CONFIG_SCTP_DBG_OBJCNT is not set
+# CONFIG_SCTP_HMAC_NONE is not set
+# CONFIG_SCTP_HMAC_SHA1 is not set
+CONFIG_SCTP_HMAC_MD5=y
+CONFIG_RDS=m
+CONFIG_RDS_TCP=m
+# CONFIG_RDS_DEBUG is not set
+CONFIG_TIPC=m
+CONFIG_TIPC_ADVANCED=y
+CONFIG_TIPC_PORTS=8191
+CONFIG_TIPC_LOG=0
+# CONFIG_TIPC_DEBUG is not set
+CONFIG_ATM=m
+CONFIG_ATM_CLIP=m
+# CONFIG_ATM_CLIP_NO_ICMP is not set
+CONFIG_ATM_LANE=m
+CONFIG_ATM_MPOA=m
+CONFIG_ATM_BR2684=m
+# CONFIG_ATM_BR2684_IPFILTER is not set
+# CONFIG_L2TP is not set
+CONFIG_STP=m
+CONFIG_GARP=m
+CONFIG_BRIDGE=m
+CONFIG_BRIDGE_IGMP_SNOOPING=y
+# CONFIG_NET_DSA is not set
+CONFIG_VLAN_8021Q=m
+CONFIG_VLAN_8021Q_GVRP=y
+CONFIG_DECNET=m
+# CONFIG_DECNET_ROUTER is not set
+CONFIG_LLC=m
+CONFIG_LLC2=m
+CONFIG_IPX=m
+# CONFIG_IPX_INTERN is not set
+CONFIG_ATALK=m
+CONFIG_DEV_APPLETALK=m
+CONFIG_IPDDP=m
+CONFIG_IPDDP_ENCAP=y
+CONFIG_IPDDP_DECAP=y
+CONFIG_X25=m
+CONFIG_LAPB=m
+CONFIG_ECONET=m
+CONFIG_ECONET_AUNUDP=y
+CONFIG_ECONET_NATIVE=y
+# CONFIG_WAN_ROUTER is not set
+# CONFIG_PHONET is not set
+# CONFIG_IEEE802154 is not set
+CONFIG_NET_SCHED=y
+
+#
+# Queueing/Scheduling
+#
+CONFIG_NET_SCH_CBQ=m
+CONFIG_NET_SCH_HTB=m
+CONFIG_NET_SCH_HFSC=m
+CONFIG_NET_SCH_ATM=m
+CONFIG_NET_SCH_PRIO=m
+CONFIG_NET_SCH_MULTIQ=m
+CONFIG_NET_SCH_RED=m
+# CONFIG_NET_SCH_SFB is not set
+CONFIG_NET_SCH_SFQ=m
+CONFIG_NET_SCH_TEQL=m
+CONFIG_NET_SCH_TBF=m
+CONFIG_NET_SCH_GRED=m
+CONFIG_NET_SCH_DSMARK=m
+CONFIG_NET_SCH_NETEM=m
+CONFIG_NET_SCH_DRR=m
+# CONFIG_NET_SCH_MQPRIO is not set
+# CONFIG_NET_SCH_CHOKE is not set
+# CONFIG_NET_SCH_QFQ is not set
+CONFIG_NET_SCH_INGRESS=m
+
+#
+# Classification
+#
+CONFIG_NET_CLS=y
+CONFIG_NET_CLS_BASIC=m
+CONFIG_NET_CLS_TCINDEX=m
+CONFIG_NET_CLS_ROUTE4=m
+CONFIG_NET_CLS_FW=m
+CONFIG_NET_CLS_U32=m
+CONFIG_CLS_U32_PERF=y
+CONFIG_CLS_U32_MARK=y
+CONFIG_NET_CLS_RSVP=m
+CONFIG_NET_CLS_RSVP6=m
+CONFIG_NET_CLS_FLOW=m
+CONFIG_NET_CLS_CGROUP=y
+CONFIG_NET_EMATCH=y
+CONFIG_NET_EMATCH_STACK=32
+CONFIG_NET_EMATCH_CMP=m
+CONFIG_NET_EMATCH_NBYTE=m
+CONFIG_NET_EMATCH_U32=m
+CONFIG_NET_EMATCH_META=m
+CONFIG_NET_EMATCH_TEXT=m
+CONFIG_NET_CLS_ACT=y
+CONFIG_NET_ACT_POLICE=m
+CONFIG_NET_ACT_GACT=m
+CONFIG_GACT_PROB=y
+CONFIG_NET_ACT_MIRRED=m
+CONFIG_NET_ACT_IPT=m
+CONFIG_NET_ACT_NAT=m
+CONFIG_NET_ACT_PEDIT=m
+CONFIG_NET_ACT_SIMP=m
+CONFIG_NET_ACT_SKBEDIT=m
+# CONFIG_NET_ACT_CSUM is not set
+CONFIG_NET_CLS_IND=y
+CONFIG_NET_SCH_FIFO=y
+CONFIG_DCB=y
+CONFIG_DNS_RESOLVER=y
+# CONFIG_BATMAN_ADV is not set
+CONFIG_RPS=y
+CONFIG_RFS_ACCEL=y
+CONFIG_XPS=y
+
+#
+# Network testing
+#
+CONFIG_NET_PKTGEN=m
+# CONFIG_NET_TCPPROBE is not set
+CONFIG_NET_DROP_MONITOR=y
+# CONFIG_HAMRADIO is not set
+CONFIG_CAN=m
+CONFIG_CAN_RAW=m
+CONFIG_CAN_BCM=m
+# CONFIG_CAN_GW is not set
+
+#
+# CAN Device Drivers
+#
+CONFIG_CAN_VCAN=m
+# CONFIG_CAN_SLCAN is not set
+CONFIG_CAN_DEV=m
+CONFIG_CAN_CALC_BITTIMING=y
+# CONFIG_CAN_MCP251X is not set
+# CONFIG_PCH_CAN is not set
+CONFIG_CAN_SJA1000=m
+CONFIG_CAN_SJA1000_PLATFORM=m
+CONFIG_CAN_EMS_PCI=m
+# CONFIG_CAN_PEAK_PCI is not set
+CONFIG_CAN_KVASER_PCI=m
+# CONFIG_CAN_PLX_PCI is not set
+# CONFIG_CAN_C_CAN is not set
+
+#
+# CAN USB interfaces
+#
+CONFIG_CAN_EMS_USB=m
+# CONFIG_CAN_ESD_USB2 is not set
+# CONFIG_CAN_SOFTING is not set
+# CONFIG_CAN_DEBUG_DEVICES is not set
+CONFIG_IRDA=m
+
+#
+# IrDA protocols
+#
+CONFIG_IRLAN=m
+CONFIG_IRCOMM=m
+# CONFIG_IRDA_ULTRA is not set
+
+#
+# IrDA options
+#
+CONFIG_IRDA_CACHE_LAST_LSAP=y
+CONFIG_IRDA_FAST_RR=y
+# CONFIG_IRDA_DEBUG is not set
+
+#
+# Infrared-port device drivers
+#
+
+#
+# SIR device drivers
+#
+CONFIG_IRTTY_SIR=m
+
+#
+# Dongle support
+#
+CONFIG_DONGLE=y
+CONFIG_ESI_DONGLE=m
+CONFIG_ACTISYS_DONGLE=m
+CONFIG_TEKRAM_DONGLE=m
+CONFIG_TOIM3232_DONGLE=m
+CONFIG_LITELINK_DONGLE=m
+CONFIG_MA600_DONGLE=m
+CONFIG_GIRBIL_DONGLE=m
+CONFIG_MCP2120_DONGLE=m
+CONFIG_OLD_BELKIN_DONGLE=m
+CONFIG_ACT200L_DONGLE=m
+CONFIG_KINGSUN_DONGLE=m
+CONFIG_KSDAZZLE_DONGLE=m
+CONFIG_KS959_DONGLE=m
+
+#
+# FIR device drivers
+#
+CONFIG_USB_IRDA=m
+CONFIG_SIGMATEL_FIR=m
+CONFIG_NSC_FIR=m
+CONFIG_WINBOND_FIR=m
+# CONFIG_TOSHIBA_FIR is not set
+CONFIG_SMC_IRCC_FIR=m
+CONFIG_ALI_FIR=m
+CONFIG_VLSI_FIR=m
+CONFIG_VIA_FIR=m
+CONFIG_MCS_FIR=m
+# CONFIG_BT is not set
+CONFIG_AF_RXRPC=m
+# CONFIG_AF_RXRPC_DEBUG is not set
+# CONFIG_RXKAD is not set
+CONFIG_FIB_RULES=y
+CONFIG_WIRELESS=y
+CONFIG_WEXT_CORE=y
+CONFIG_WEXT_PROC=y
+CONFIG_CFG80211=m
+# CONFIG_NL80211_TESTMODE is not set
+# CONFIG_CFG80211_DEVELOPER_WARNINGS is not set
+# CONFIG_CFG80211_REG_DEBUG is not set
+CONFIG_CFG80211_DEFAULT_PS=y
+# CONFIG_CFG80211_DEBUGFS is not set
+# CONFIG_CFG80211_INTERNAL_REGDB is not set
+CONFIG_CFG80211_WEXT=y
+# CONFIG_WIRELESS_EXT_SYSFS is not set
+CONFIG_LIB80211=m
+# CONFIG_LIB80211_DEBUG is not set
+CONFIG_MAC80211=m
+CONFIG_MAC80211_HAS_RC=y
+CONFIG_MAC80211_RC_MINSTREL=y
+CONFIG_MAC80211_RC_MINSTREL_HT=y
+CONFIG_MAC80211_RC_DEFAULT_MINSTREL=y
+CONFIG_MAC80211_RC_DEFAULT="minstrel_ht"
+CONFIG_MAC80211_MESH=y
+CONFIG_MAC80211_LEDS=y
+# CONFIG_MAC80211_DEBUGFS is not set
+# CONFIG_MAC80211_DEBUG_MENU is not set
+# CONFIG_WIMAX is not set
+# CONFIG_RFKILL is not set
+# CONFIG_RFKILL_REGULATOR is not set
+CONFIG_NET_9P=m
+# CONFIG_NET_9P_DEBUG is not set
+# CONFIG_CAIF is not set
+# CONFIG_CEPH_LIB is not set
+# CONFIG_NFC is not set
+
+#
+# Device Drivers
+#
+
+#
+# Generic Driver Options
+#
+CONFIG_UEVENT_HELPER_PATH=""
+CONFIG_DEVTMPFS=y
+# CONFIG_DEVTMPFS_MOUNT is not set
+CONFIG_STANDALONE=y
+CONFIG_PREVENT_FIRMWARE_BUILD=y
+CONFIG_FW_LOADER=y
+# CONFIG_FIRMWARE_IN_KERNEL is not set
+CONFIG_EXTRA_FIRMWARE=""
+# CONFIG_DEBUG_DRIVER is not set
+# CONFIG_DEBUG_DEVRES is not set
+# CONFIG_SYS_HYPERVISOR is not set
+CONFIG_REGMAP=y
+CONFIG_REGMAP_I2C=m
+CONFIG_CONNECTOR=m
+CONFIG_MTD=m
+# CONFIG_MTD_TESTS is not set
+CONFIG_MTD_REDBOOT_PARTS=m
+CONFIG_MTD_REDBOOT_DIRECTORY_BLOCK=-1
+# CONFIG_MTD_REDBOOT_PARTS_UNALLOCATED is not set
+# CONFIG_MTD_REDBOOT_PARTS_READONLY is not set
+CONFIG_MTD_AR7_PARTS=m
+
+#
+# User Modules And Translation Layers
+#
+CONFIG_MTD_CHAR=m
+CONFIG_MTD_BLKDEVS=m
+CONFIG_MTD_BLOCK=m
+CONFIG_MTD_BLOCK_RO=m
+CONFIG_FTL=m
+CONFIG_NFTL=m
+CONFIG_NFTL_RW=y
+CONFIG_INFTL=m
+CONFIG_RFD_FTL=m
+CONFIG_SSFDC=m
+# CONFIG_SM_FTL is not set
+CONFIG_MTD_OOPS=m
+# CONFIG_MTD_SWAP is not set
+
+#
+# RAM/ROM/Flash chip drivers
+#
+CONFIG_MTD_CFI=m
+CONFIG_MTD_JEDECPROBE=m
+CONFIG_MTD_GEN_PROBE=m
+# CONFIG_MTD_CFI_ADV_OPTIONS is not set
+CONFIG_MTD_MAP_BANK_WIDTH_1=y
+CONFIG_MTD_MAP_BANK_WIDTH_2=y
+CONFIG_MTD_MAP_BANK_WIDTH_4=y
+# CONFIG_MTD_MAP_BANK_WIDTH_8 is not set
+# CONFIG_MTD_MAP_BANK_WIDTH_16 is not set
+# CONFIG_MTD_MAP_BANK_WIDTH_32 is not set
+CONFIG_MTD_CFI_I1=y
+CONFIG_MTD_CFI_I2=y
+# CONFIG_MTD_CFI_I4 is not set
+# CONFIG_MTD_CFI_I8 is not set
+CONFIG_MTD_CFI_INTELEXT=m
+CONFIG_MTD_CFI_AMDSTD=m
+CONFIG_MTD_CFI_STAA=m
+CONFIG_MTD_CFI_UTIL=m
+CONFIG_MTD_RAM=m
+CONFIG_MTD_ROM=m
+CONFIG_MTD_ABSENT=m
+
+#
+# Mapping drivers for chip access
+#
+CONFIG_MTD_COMPLEX_MAPPINGS=y
+CONFIG_MTD_PHYSMAP=m
+# CONFIG_MTD_PHYSMAP_COMPAT is not set
+CONFIG_MTD_SC520CDP=m
+CONFIG_MTD_NETSC520=m
+CONFIG_MTD_TS5500=m
+CONFIG_MTD_SBC_GXX=m
+# CONFIG_MTD_AMD76XROM is not set
+# CONFIG_MTD_ICHXROM is not set
+# CONFIG_MTD_ESB2ROM is not set
+# CONFIG_MTD_CK804XROM is not set
+# CONFIG_MTD_SCB2_FLASH is not set
+CONFIG_MTD_NETtel=m
+# CONFIG_MTD_L440GX is not set
+CONFIG_MTD_PCI=m
+# CONFIG_MTD_GPIO_ADDR is not set
+CONFIG_MTD_INTEL_VR_NOR=m
+CONFIG_MTD_PLATRAM=m
+# CONFIG_MTD_LATCH_ADDR is not set
+
+#
+# Self-contained MTD device drivers
+#
+CONFIG_MTD_PMC551=m
+# CONFIG_MTD_PMC551_BUGFIX is not set
+# CONFIG_MTD_PMC551_DEBUG is not set
+CONFIG_MTD_DATAFLASH=m
+# CONFIG_MTD_DATAFLASH_WRITE_VERIFY is not set
+# CONFIG_MTD_DATAFLASH_OTP is not set
+CONFIG_MTD_M25P80=m
+CONFIG_M25PXX_USE_FAST_READ=y
+CONFIG_MTD_SST25L=m
+CONFIG_MTD_SLRAM=m
+CONFIG_MTD_PHRAM=m
+CONFIG_MTD_MTDRAM=m
+CONFIG_MTDRAM_TOTAL_SIZE=4096
+CONFIG_MTDRAM_ERASE_SIZE=128
+CONFIG_MTD_BLOCK2MTD=m
+
+#
+# Disk-On-Chip Device Drivers
+#
+CONFIG_MTD_DOC2000=m
+CONFIG_MTD_DOC2001=m
+CONFIG_MTD_DOC2001PLUS=m
+# CONFIG_MTD_DOCG3 is not set
+CONFIG_MTD_DOCPROBE=m
+CONFIG_MTD_DOCECC=m
+# CONFIG_MTD_DOCPROBE_ADVANCED is not set
+CONFIG_MTD_DOCPROBE_ADDRESS=0x0
+CONFIG_MTD_NAND_ECC=m
+# CONFIG_MTD_NAND_ECC_SMC is not set
+CONFIG_MTD_NAND=m
+# CONFIG_MTD_NAND_VERIFY_WRITE is not set
+# CONFIG_MTD_NAND_ECC_BCH is not set
+# CONFIG_MTD_SM_COMMON is not set
+# CONFIG_MTD_NAND_MUSEUM_IDS is not set
+# CONFIG_MTD_NAND_DENALI is not set
+CONFIG_MTD_NAND_IDS=m
+# CONFIG_MTD_NAND_RICOH is not set
+CONFIG_MTD_NAND_DISKONCHIP=m
+# CONFIG_MTD_NAND_DISKONCHIP_PROBE_ADVANCED is not set
+CONFIG_MTD_NAND_DISKONCHIP_PROBE_ADDRESS=0
+# CONFIG_MTD_NAND_DISKONCHIP_BBTWRITE is not set
+CONFIG_MTD_NAND_CAFE=m
+# CONFIG_MTD_NAND_CS553X is not set
+CONFIG_MTD_NAND_NANDSIM=m
+CONFIG_MTD_NAND_PLATFORM=m
+CONFIG_MTD_ALAUDA=m
+CONFIG_MTD_ONENAND=m
+CONFIG_MTD_ONENAND_VERIFY_WRITE=y
+CONFIG_MTD_ONENAND_GENERIC=m
+# CONFIG_MTD_ONENAND_OTP is not set
+CONFIG_MTD_ONENAND_2X_PROGRAM=y
+CONFIG_MTD_ONENAND_SIM=m
+
+#
+# LPDDR flash memory drivers
+#
+CONFIG_MTD_LPDDR=m
+CONFIG_MTD_QINFO_PROBE=m
+CONFIG_MTD_UBI=m
+CONFIG_MTD_UBI_WL_THRESHOLD=4096
+CONFIG_MTD_UBI_BEB_RESERVE=1
+# CONFIG_MTD_UBI_GLUEBI is not set
+# CONFIG_MTD_UBI_DEBUG is not set
+# CONFIG_PARPORT is not set
+CONFIG_PNP=y
+# CONFIG_PNP_DEBUG_MESSAGES is not set
+
+#
+# Protocols
+#
+CONFIG_PNPACPI=y
+CONFIG_BLK_DEV=y
+CONFIG_BLK_DEV_FD=m
+CONFIG_BLK_CPQ_DA=m
+# CONFIG_BLK_CPQ_CISS_DA is not set
+# CONFIG_BLK_DEV_DAC960 is not set
+# CONFIG_BLK_DEV_UMEM is not set
+# CONFIG_BLK_DEV_COW_COMMON is not set
+CONFIG_BLK_DEV_LOOP=y
+CONFIG_BLK_DEV_LOOP_MIN_COUNT=8
+# CONFIG_BLK_DEV_CRYPTOLOOP is not set
+# CONFIG_BLK_DEV_DRBD is not set
+CONFIG_BLK_DEV_NBD=m
+CONFIG_BLK_DEV_OSD=m
+CONFIG_BLK_DEV_SX8=m
+# CONFIG_BLK_DEV_UB is not set
+CONFIG_BLK_DEV_RAM=m
+CONFIG_BLK_DEV_RAM_COUNT=16
+CONFIG_BLK_DEV_RAM_SIZE=8192
+# CONFIG_BLK_DEV_XIP is not set
+CONFIG_CDROM_PKTCDVD=m
+CONFIG_CDROM_PKTCDVD_BUFFERS=8
+# CONFIG_CDROM_PKTCDVD_WCACHE is not set
+CONFIG_ATA_OVER_ETH=m
+# CONFIG_BLK_DEV_HD is not set
+# CONFIG_BLK_DEV_RBD is not set
+# CONFIG_SENSORS_LIS3LV02D is not set
+CONFIG_MISC_DEVICES=y
+# CONFIG_AD525X_DPOT is not set
+# CONFIG_IBM_ASM is not set
+CONFIG_HWLAT_DETECTOR=m
+# CONFIG_PHANTOM is not set
+# CONFIG_INTEL_MID_PTI is not set
+CONFIG_SGI_IOC4=m
+CONFIG_TIFM_CORE=m
+CONFIG_TIFM_7XX1=m
+# CONFIG_ICS932S401 is not set
+CONFIG_ENCLOSURE_SERVICES=m
+# CONFIG_HP_ILO is not set
+# CONFIG_APDS9802ALS is not set
+# CONFIG_ISL29003 is not set
+# CONFIG_ISL29020 is not set
+# CONFIG_SENSORS_TSL2550 is not set
+# CONFIG_SENSORS_BH1780 is not set
+# CONFIG_SENSORS_BH1770 is not set
+# CONFIG_SENSORS_APDS990X is not set
+# CONFIG_HMC6352 is not set
+# CONFIG_DS1682 is not set
+# CONFIG_TI_DAC7512 is not set
+# CONFIG_VMWARE_BALLOON is not set
+# CONFIG_BMP085 is not set
+# CONFIG_PCH_PHUB is not set
+# CONFIG_USB_SWITCH_FSA9480 is not set
+CONFIG_C2PORT=m
+CONFIG_C2PORT_DURAMAR_2150=m
+
+#
+# EEPROM support
+#
+CONFIG_EEPROM_AT24=m
+CONFIG_EEPROM_AT25=m
+CONFIG_EEPROM_LEGACY=m
+CONFIG_EEPROM_MAX6875=m
+CONFIG_EEPROM_93CX6=m
+# CONFIG_EEPROM_93XX46 is not set
+CONFIG_CB710_CORE=m
+# CONFIG_CB710_DEBUG is not set
+CONFIG_CB710_DEBUG_ASSUMPTIONS=y
+# CONFIG_IWMC3200TOP is not set
+
+#
+# Texas Instruments shared transport line discipline
+#
+# CONFIG_TI_ST is not set
+# CONFIG_SENSORS_LIS3_I2C is not set
+
+#
+# Altera FPGA firmware download module
+#
+# CONFIG_ALTERA_STAPL is not set
+CONFIG_HAVE_IDE=y
+# CONFIG_IDE is not set
+
+#
+# SCSI device support
+#
+CONFIG_SCSI_MOD=y
+CONFIG_RAID_ATTRS=m
+CONFIG_SCSI=y
+CONFIG_SCSI_DMA=y
+CONFIG_SCSI_TGT=m
+CONFIG_SCSI_NETLINK=y
+CONFIG_SCSI_PROC_FS=y
+
+#
+# SCSI support type (disk, tape, CD-ROM)
+#
+CONFIG_BLK_DEV_SD=y
+# CONFIG_CHR_DEV_ST is not set
+# CONFIG_CHR_DEV_OSST is not set
+CONFIG_BLK_DEV_SR=m
+CONFIG_BLK_DEV_SR_VENDOR=y
+CONFIG_CHR_DEV_SG=m
+# CONFIG_CHR_DEV_SCH is not set
+# CONFIG_SCSI_ENCLOSURE is not set
+CONFIG_SCSI_MULTI_LUN=y
+CONFIG_SCSI_CONSTANTS=y
+CONFIG_SCSI_LOGGING=y
+CONFIG_SCSI_SCAN_ASYNC=y
+CONFIG_SCSI_WAIT_SCAN=m
+
+#
+# SCSI Transports
+#
+CONFIG_SCSI_SPI_ATTRS=m
+CONFIG_SCSI_FC_ATTRS=m
+CONFIG_SCSI_FC_TGT_ATTRS=y
+CONFIG_SCSI_ISCSI_ATTRS=m
+CONFIG_SCSI_SAS_ATTRS=m
+CONFIG_SCSI_SAS_LIBSAS=m
+CONFIG_SCSI_SAS_ATA=y
+CONFIG_SCSI_SAS_HOST_SMP=y
+CONFIG_SCSI_SRP_ATTRS=m
+CONFIG_SCSI_SRP_TGT_ATTRS=y
+CONFIG_SCSI_LOWLEVEL=y
+# CONFIG_ISCSI_TCP is not set
+CONFIG_ISCSI_BOOT_SYSFS=y
+# CONFIG_SCSI_CXGB3_ISCSI is not set
+# CONFIG_SCSI_CXGB4_ISCSI is not set
+CONFIG_SCSI_BNX2_ISCSI=m
+# CONFIG_SCSI_BNX2X_FCOE is not set
+# CONFIG_BE2ISCSI is not set
+CONFIG_BLK_DEV_3W_XXXX_RAID=m
+CONFIG_SCSI_HPSA=m
+CONFIG_SCSI_3W_9XXX=m
+CONFIG_SCSI_3W_SAS=m
+CONFIG_SCSI_ACARD=m
+CONFIG_SCSI_AACRAID=m
+CONFIG_SCSI_AIC7XXX=m
+CONFIG_AIC7XXX_CMDS_PER_DEVICE=8
+CONFIG_AIC7XXX_RESET_DELAY_MS=15000
+CONFIG_AIC7XXX_DEBUG_ENABLE=y
+CONFIG_AIC7XXX_DEBUG_MASK=0
+CONFIG_AIC7XXX_REG_PRETTY_PRINT=y
+CONFIG_SCSI_AIC7XXX_OLD=m
+CONFIG_SCSI_AIC79XX=m
+CONFIG_AIC79XX_CMDS_PER_DEVICE=32
+CONFIG_AIC79XX_RESET_DELAY_MS=15000
+CONFIG_AIC79XX_DEBUG_ENABLE=y
+CONFIG_AIC79XX_DEBUG_MASK=0
+CONFIG_AIC79XX_REG_PRETTY_PRINT=y
+CONFIG_SCSI_AIC94XX=m
+# CONFIG_AIC94XX_DEBUG is not set
+CONFIG_SCSI_MVSAS=m
+# CONFIG_SCSI_MVSAS_DEBUG is not set
+# CONFIG_SCSI_MVSAS_TASKLET is not set
+# CONFIG_SCSI_MVUMI is not set
+CONFIG_SCSI_DPT_I2O=m
+CONFIG_SCSI_ADVANSYS=m
+CONFIG_SCSI_ARCMSR=m
+CONFIG_MEGARAID_NEWGEN=y
+CONFIG_MEGARAID_MM=m
+CONFIG_MEGARAID_MAILBOX=m
+CONFIG_MEGARAID_LEGACY=m
+CONFIG_MEGARAID_SAS=m
+CONFIG_SCSI_MPT2SAS=m
+CONFIG_SCSI_MPT2SAS_MAX_SGE=128
+# CONFIG_SCSI_MPT2SAS_LOGGING is not set
+CONFIG_SCSI_HPTIOP=m
+CONFIG_SCSI_BUSLOGIC=m
+# CONFIG_SCSI_FLASHPOINT is not set
+CONFIG_VMWARE_PVSCSI=m
+CONFIG_LIBFC=m
+CONFIG_LIBFCOE=m
+CONFIG_FCOE=m
+CONFIG_FCOE_FNIC=m
+CONFIG_SCSI_DMX3191D=m
+CONFIG_SCSI_EATA=m
+CONFIG_SCSI_EATA_TAGGED_QUEUE=y
+CONFIG_SCSI_EATA_LINKED_COMMANDS=y
+CONFIG_SCSI_EATA_MAX_TAGS=16
+CONFIG_SCSI_FUTURE_DOMAIN=m
+CONFIG_SCSI_GDTH=m
+# CONFIG_SCSI_ISCI is not set
+CONFIG_SCSI_IPS=m
+CONFIG_SCSI_INITIO=m
+# CONFIG_SCSI_INIA100 is not set
+CONFIG_SCSI_STEX=m
+CONFIG_SCSI_SYM53C8XX_2=m
+CONFIG_SCSI_SYM53C8XX_DMA_ADDRESSING_MODE=1
+CONFIG_SCSI_SYM53C8XX_DEFAULT_TAGS=16
+CONFIG_SCSI_SYM53C8XX_MAX_TAGS=64
+CONFIG_SCSI_SYM53C8XX_MMIO=y
+CONFIG_SCSI_IPR=m
+# CONFIG_SCSI_IPR_TRACE is not set
+# CONFIG_SCSI_IPR_DUMP is not set
+CONFIG_SCSI_QLOGIC_1280=m
+CONFIG_SCSI_QLA_FC=m
+CONFIG_SCSI_QLA_ISCSI=m
+CONFIG_SCSI_LPFC=m
+# CONFIG_SCSI_LPFC_DEBUG_FS is not set
+CONFIG_SCSI_DC395x=m
+CONFIG_SCSI_DC390T=m
+# CONFIG_SCSI_NSP32 is not set
+CONFIG_SCSI_DEBUG=m
+CONFIG_SCSI_PMCRAID=m
+CONFIG_SCSI_PM8001=m
+CONFIG_SCSI_SRP=m
+CONFIG_SCSI_BFA_FC=m
+CONFIG_SCSI_DH=m
+CONFIG_SCSI_DH_RDAC=m
+CONFIG_SCSI_DH_HP_SW=m
+CONFIG_SCSI_DH_EMC=m
+CONFIG_SCSI_DH_ALUA=m
+CONFIG_SCSI_OSD_INITIATOR=m
+CONFIG_SCSI_OSD_ULD=m
+CONFIG_SCSI_OSD_DPRINT_SENSE=1
+# CONFIG_SCSI_OSD_DEBUG is not set
+CONFIG_ATA=y
+# CONFIG_ATA_NONSTANDARD is not set
+CONFIG_ATA_VERBOSE_ERROR=y
+CONFIG_ATA_ACPI=y
+CONFIG_SATA_PMP=y
+
+#
+# Controllers with non-SFF native interface
+#
+CONFIG_SATA_AHCI=m
+# CONFIG_SATA_AHCI_PLATFORM is not set
+# CONFIG_SATA_INIC162X is not set
+# CONFIG_SATA_ACARD_AHCI is not set
+# CONFIG_SATA_SIL24 is not set
+CONFIG_ATA_SFF=y
+
+#
+# SFF controllers with custom DMA interface
+#
+# CONFIG_PDC_ADMA is not set
+# CONFIG_SATA_QSTOR is not set
+# CONFIG_SATA_SX4 is not set
+CONFIG_ATA_BMDMA=y
+
+#
+# SATA SFF controllers with BMDMA
+#
+# CONFIG_ATA_PIIX is not set
+# CONFIG_SATA_MV is not set
+# CONFIG_SATA_NV is not set
+# CONFIG_SATA_PROMISE is not set
+# CONFIG_SATA_SIL is not set
+# CONFIG_SATA_SIS is not set
+# CONFIG_SATA_SVW is not set
+# CONFIG_SATA_ULI is not set
+# CONFIG_SATA_VIA is not set
+# CONFIG_SATA_VITESSE is not set
+
+#
+# PATA SFF controllers with BMDMA
+#
+# CONFIG_PATA_ALI is not set
+# CONFIG_PATA_AMD is not set
+# CONFIG_PATA_ARASAN_CF is not set
+# CONFIG_PATA_ARTOP is not set
+# CONFIG_PATA_ATIIXP is not set
+# CONFIG_PATA_ATP867X is not set
+# CONFIG_PATA_CMD64X is not set
+# CONFIG_PATA_CS5520 is not set
+# CONFIG_PATA_CS5530 is not set
+# CONFIG_PATA_CS5535 is not set
+# CONFIG_PATA_CS5536 is not set
+# CONFIG_PATA_CYPRESS is not set
+# CONFIG_PATA_EFAR is not set
+# CONFIG_PATA_HPT366 is not set
+# CONFIG_PATA_HPT37X is not set
+# CONFIG_PATA_HPT3X2N is not set
+# CONFIG_PATA_HPT3X3 is not set
+# CONFIG_PATA_IT8213 is not set
+# CONFIG_PATA_IT821X is not set
+# CONFIG_PATA_JMICRON is not set
+# CONFIG_PATA_MARVELL is not set
+# CONFIG_PATA_NETCELL is not set
+# CONFIG_PATA_NINJA32 is not set
+# CONFIG_PATA_NS87415 is not set
+# CONFIG_PATA_OLDPIIX is not set
+# CONFIG_PATA_OPTIDMA is not set
+# CONFIG_PATA_PDC2027X is not set
+# CONFIG_PATA_PDC_OLD is not set
+# CONFIG_PATA_RADISYS is not set
+# CONFIG_PATA_RDC is not set
+# CONFIG_PATA_SC1200 is not set
+CONFIG_PATA_SCH=y
+# CONFIG_PATA_SERVERWORKS is not set
+# CONFIG_PATA_SIL680 is not set
+# CONFIG_PATA_SIS is not set
+# CONFIG_PATA_TOSHIBA is not set
+# CONFIG_PATA_TRIFLEX is not set
+# CONFIG_PATA_VIA is not set
+# CONFIG_PATA_WINBOND is not set
+
+#
+# PIO-only SFF controllers
+#
+# CONFIG_PATA_CMD640_PCI is not set
+CONFIG_PATA_MPIIX=m
+# CONFIG_PATA_NS87410 is not set
+# CONFIG_PATA_OPTI is not set
+# CONFIG_PATA_RZ1000 is not set
+
+#
+# Generic fallback / legacy drivers
+#
+# CONFIG_PATA_ACPI is not set
+CONFIG_ATA_GENERIC=y
+# CONFIG_PATA_LEGACY is not set
+# CONFIG_MD is not set
+# CONFIG_TARGET_CORE is not set
+# CONFIG_FUSION is not set
+
+#
+# IEEE 1394 (FireWire) support
+#
+CONFIG_FIREWIRE=m
+CONFIG_FIREWIRE_OHCI=m
+CONFIG_FIREWIRE_OHCI_DEBUG=y
+CONFIG_FIREWIRE_SBP2=m
+CONFIG_FIREWIRE_NET=m
+# CONFIG_FIREWIRE_NOSY is not set
+# CONFIG_I2O is not set
+# CONFIG_MACINTOSH_DRIVERS is not set
+CONFIG_NETDEVICES=y
+CONFIG_NET_CORE=y
+# CONFIG_BONDING is not set
+# CONFIG_DUMMY is not set
+# CONFIG_EQUALIZER is not set
+# CONFIG_NET_FC is not set
+CONFIG_MII=y
+CONFIG_IFB=m
+# CONFIG_MACVLAN is not set
+# CONFIG_NETPOLL is not set
+# CONFIG_NET_POLL_CONTROLLER is not set
+CONFIG_TUN=m
+# CONFIG_VETH is not set
+# CONFIG_ARCNET is not set
+# CONFIG_ATM_DRIVERS is not set
+
+#
+# CAIF transport drivers
+#
+CONFIG_ETHERNET=y
+# CONFIG_NET_VENDOR_3COM is not set
+# CONFIG_NET_VENDOR_ADAPTEC is not set
+# CONFIG_NET_VENDOR_ALTEON is not set
+# CONFIG_NET_VENDOR_AMD is not set
+# CONFIG_NET_VENDOR_ATHEROS is not set
+CONFIG_NET_VENDOR_BROADCOM=y
+# CONFIG_B44 is not set
+CONFIG_BNX2=m
+CONFIG_CNIC=m
+# CONFIG_TIGON3 is not set
+# CONFIG_BNX2X is not set
+# CONFIG_NET_VENDOR_BROCADE is not set
+# CONFIG_NET_VENDOR_CHELSIO is not set
+# CONFIG_NET_VENDOR_CISCO is not set
+# CONFIG_DNET is not set
+# CONFIG_NET_VENDOR_DEC is not set
+# CONFIG_NET_VENDOR_DLINK is not set
+# CONFIG_NET_VENDOR_EMULEX is not set
+# CONFIG_NET_VENDOR_EXAR is not set
+# CONFIG_NET_VENDOR_HP is not set
+# CONFIG_NET_VENDOR_INTEL is not set
+# CONFIG_IP1000 is not set
+# CONFIG_JME is not set
+# CONFIG_NET_VENDOR_MARVELL is not set
+# CONFIG_NET_VENDOR_MELLANOX is not set
+# CONFIG_NET_VENDOR_MICREL is not set
+# CONFIG_NET_VENDOR_MICROCHIP is not set
+# CONFIG_NET_VENDOR_MYRI is not set
+# CONFIG_FEALNX is not set
+# CONFIG_NET_VENDOR_NATSEMI is not set
+# CONFIG_NET_VENDOR_NVIDIA is not set
+# CONFIG_NET_VENDOR_OKI is not set
+# CONFIG_ETHOC is not set
+# CONFIG_NET_PACKET_ENGINE is not set
+# CONFIG_NET_VENDOR_QLOGIC is not set
+CONFIG_NET_VENDOR_REALTEK=y
+# CONFIG_8139CP is not set
+# CONFIG_8139TOO is not set
+CONFIG_R8169=y
+# CONFIG_NET_VENDOR_RDC is not set
+# CONFIG_NET_VENDOR_SEEQ is not set
+# CONFIG_NET_VENDOR_SILAN is not set
+# CONFIG_NET_VENDOR_SIS is not set
+# CONFIG_SFC is not set
+# CONFIG_NET_VENDOR_SMSC is not set
+# CONFIG_NET_VENDOR_STMICRO is not set
+# CONFIG_NET_VENDOR_SUN is not set
+# CONFIG_NET_VENDOR_TEHUTI is not set
+# CONFIG_NET_VENDOR_TI is not set
+# CONFIG_NET_VENDOR_VIA is not set
+# CONFIG_FDDI is not set
+# CONFIG_HIPPI is not set
+# CONFIG_NET_SB1000 is not set
+CONFIG_PHYLIB=m
+
+#
+# MII PHY device drivers
+#
+CONFIG_MARVELL_PHY=m
+CONFIG_DAVICOM_PHY=m
+CONFIG_QSEMI_PHY=m
+CONFIG_LXT_PHY=m
+CONFIG_CICADA_PHY=m
+CONFIG_VITESSE_PHY=m
+CONFIG_SMSC_PHY=m
+CONFIG_BROADCOM_PHY=m
+CONFIG_ICPLUS_PHY=m
+CONFIG_REALTEK_PHY=m
+CONFIG_NATIONAL_PHY=m
+CONFIG_STE10XP=m
+CONFIG_LSI_ET1011C_PHY=m
+# CONFIG_MICREL_PHY is not set
+CONFIG_MDIO_BITBANG=m
+# CONFIG_MDIO_GPIO is not set
+# CONFIG_PPP is not set
+# CONFIG_SLIP is not set
+# CONFIG_TR is not set
+
+#
+# USB Network Adapters
+#
+CONFIG_USB_CATC=m
+CONFIG_USB_KAWETH=m
+CONFIG_USB_PEGASUS=m
+CONFIG_USB_RTL8150=m
+CONFIG_USB_USBNET=m
+CONFIG_USB_NET_AX8817X=m
+CONFIG_USB_NET_CDCETHER=m
+CONFIG_USB_NET_CDC_EEM=m
+CONFIG_USB_NET_CDC_NCM=m
+CONFIG_USB_NET_DM9601=m
+# CONFIG_USB_NET_SMSC75XX is not set
+CONFIG_USB_NET_SMSC95XX=m
+CONFIG_USB_NET_GL620A=m
+CONFIG_USB_NET_NET1080=m
+CONFIG_USB_NET_PLUSB=m
+CONFIG_USB_NET_MCS7830=m
+CONFIG_USB_NET_RNDIS_HOST=m
+CONFIG_USB_NET_CDC_SUBSET=m
+CONFIG_USB_ALI_M5632=y
+CONFIG_USB_AN2720=y
+CONFIG_USB_BELKIN=y
+CONFIG_USB_ARMLINUX=y
+CONFIG_USB_EPSON2888=y
+CONFIG_USB_KC2190=y
+CONFIG_USB_NET_ZAURUS=m
+# CONFIG_USB_NET_CX82310_ETH is not set
+# CONFIG_USB_NET_KALMIA is not set
+CONFIG_USB_NET_INT51X1=m
+CONFIG_USB_IPHETH=m
+# CONFIG_USB_SIERRA_NET is not set
+# CONFIG_USB_VL600 is not set
+# CONFIG_WLAN is not set
+
+#
+# Enable WiMAX (Networking options) to see the WiMAX drivers
+#
+# CONFIG_WAN is not set
+# CONFIG_VMXNET3 is not set
+# CONFIG_ISDN is not set
+# CONFIG_PHONE is not set
+
+#
+# Input device support
+#
+CONFIG_INPUT=y
+CONFIG_INPUT_FF_MEMLESS=y
+CONFIG_INPUT_POLLDEV=y
+CONFIG_INPUT_SPARSEKMAP=m
+
+#
+# Userland interfaces
+#
+CONFIG_INPUT_MOUSEDEV=y
+CONFIG_INPUT_MOUSEDEV_PSAUX=y
+CONFIG_INPUT_MOUSEDEV_SCREEN_X=1024
+CONFIG_INPUT_MOUSEDEV_SCREEN_Y=768
+CONFIG_INPUT_JOYDEV=y
+CONFIG_INPUT_EVDEV=y
+# CONFIG_INPUT_EVBUG is not set
+
+#
+# Input Device Drivers
+#
+CONFIG_INPUT_KEYBOARD=y
+CONFIG_KEYBOARD_ADP5588=m
+# CONFIG_KEYBOARD_ADP5589 is not set
+CONFIG_KEYBOARD_ATKBD=y
+# CONFIG_KEYBOARD_QT1070 is not set
+# CONFIG_KEYBOARD_QT2160 is not set
+CONFIG_KEYBOARD_LKKBD=m
+# CONFIG_KEYBOARD_GPIO is not set
+# CONFIG_KEYBOARD_GPIO_POLLED is not set
+# CONFIG_KEYBOARD_TCA6416 is not set
+# CONFIG_KEYBOARD_MATRIX is not set
+CONFIG_KEYBOARD_LM8323=m
+CONFIG_KEYBOARD_MAX7359=m
+# CONFIG_KEYBOARD_MCS is not set
+# CONFIG_KEYBOARD_MPR121 is not set
+CONFIG_KEYBOARD_NEWTON=m
+CONFIG_KEYBOARD_OPENCORES=m
+CONFIG_KEYBOARD_STOWAWAY=m
+CONFIG_KEYBOARD_SUNKBD=m
+CONFIG_KEYBOARD_XTKBD=m
+CONFIG_INPUT_MOUSE=y
+CONFIG_MOUSE_PS2=y
+CONFIG_MOUSE_PS2_ALPS=y
+CONFIG_MOUSE_PS2_LOGIPS2PP=y
+CONFIG_MOUSE_PS2_SYNAPTICS=y
+CONFIG_MOUSE_PS2_LIFEBOOK=y
+CONFIG_MOUSE_PS2_TRACKPOINT=y
+CONFIG_MOUSE_PS2_ELANTECH=y
+CONFIG_MOUSE_PS2_SENTELIC=y
+# CONFIG_MOUSE_PS2_TOUCHKIT is not set
+# CONFIG_MOUSE_SERIAL is not set
+# CONFIG_MOUSE_APPLETOUCH is not set
+# CONFIG_MOUSE_BCM5974 is not set
+# CONFIG_MOUSE_VSXXXAA is not set
+# CONFIG_MOUSE_GPIO is not set
+# CONFIG_MOUSE_SYNAPTICS_I2C is not set
+CONFIG_INPUT_JOYSTICK=y
+# CONFIG_JOYSTICK_ANALOG is not set
+# CONFIG_JOYSTICK_A3D is not set
+CONFIG_JOYSTICK_ADI=m
+# CONFIG_JOYSTICK_COBRA is not set
+# CONFIG_JOYSTICK_GF2K is not set
+# CONFIG_JOYSTICK_GRIP is not set
+# CONFIG_JOYSTICK_GRIP_MP is not set
+# CONFIG_JOYSTICK_GUILLEMOT is not set
+# CONFIG_JOYSTICK_INTERACT is not set
+CONFIG_JOYSTICK_SIDEWINDER=m
+CONFIG_JOYSTICK_TMDC=m
+# CONFIG_JOYSTICK_IFORCE is not set
+# CONFIG_JOYSTICK_WARRIOR is not set
+# CONFIG_JOYSTICK_MAGELLAN is not set
+# CONFIG_JOYSTICK_SPACEORB is not set
+# CONFIG_JOYSTICK_SPACEBALL is not set
+# CONFIG_JOYSTICK_STINGER is not set
+# CONFIG_JOYSTICK_TWIDJOY is not set
+# CONFIG_JOYSTICK_ZHENHUA is not set
+# CONFIG_JOYSTICK_AS5011 is not set
+# CONFIG_JOYSTICK_JOYDUMP is not set
+CONFIG_JOYSTICK_XPAD=m
+CONFIG_JOYSTICK_XPAD_FF=y
+CONFIG_JOYSTICK_XPAD_LEDS=y
+# CONFIG_INPUT_TABLET is not set
+# CONFIG_INPUT_TOUCHSCREEN is not set
+# CONFIG_INPUT_MISC is not set
+
+#
+# Hardware I/O ports
+#
+CONFIG_SERIO=y
+CONFIG_SERIO_I8042=y
+# CONFIG_SERIO_SERPORT is not set
+# CONFIG_SERIO_CT82C710 is not set
+# CONFIG_SERIO_PCIPS2 is not set
+CONFIG_SERIO_LIBPS2=y
+# CONFIG_SERIO_RAW is not set
+# CONFIG_SERIO_ALTERA_PS2 is not set
+# CONFIG_SERIO_PS2MULT is not set
+CONFIG_GAMEPORT=m
+# CONFIG_GAMEPORT_NS558 is not set
+# CONFIG_GAMEPORT_L4 is not set
+# CONFIG_GAMEPORT_EMU10K1 is not set
+# CONFIG_GAMEPORT_FM801 is not set
+
+#
+# Character devices
+#
+CONFIG_VT=y
+CONFIG_CONSOLE_TRANSLATIONS=y
+CONFIG_VT_CONSOLE=y
+CONFIG_HW_CONSOLE=y
+CONFIG_VT_HW_CONSOLE_BINDING=y
+CONFIG_UNIX98_PTYS=y
+CONFIG_DEVPTS_MULTIPLE_INSTANCES=y
+# CONFIG_LEGACY_PTYS is not set
+CONFIG_SERIAL_NONSTANDARD=y
+# CONFIG_ROCKETPORT is not set
+# CONFIG_CYCLADES is not set
+# CONFIG_MOXA_INTELLIO is not set
+# CONFIG_MOXA_SMARTIO is not set
+# CONFIG_SYNCLINK is not set
+# CONFIG_SYNCLINKMP is not set
+# CONFIG_SYNCLINK_GT is not set
+# CONFIG_NOZOMI is not set
+# CONFIG_ISI is not set
+CONFIG_N_HDLC=m
+# CONFIG_N_GSM is not set
+# CONFIG_TRACE_SINK is not set
+# CONFIG_DEVKMEM is not set
+CONFIG_STALDRV=y
+
+#
+# Serial drivers
+#
+CONFIG_SERIAL_8250=y
+CONFIG_SERIAL_8250_CONSOLE=y
+CONFIG_FIX_EARLYCON_MEM=y
+CONFIG_SERIAL_8250_PCI=y
+CONFIG_SERIAL_8250_PNP=y
+CONFIG_SERIAL_8250_NR_UARTS=32
+CONFIG_SERIAL_8250_RUNTIME_UARTS=4
+CONFIG_SERIAL_8250_EXTENDED=y
+CONFIG_SERIAL_8250_MANY_PORTS=y
+CONFIG_SERIAL_8250_SHARE_IRQ=y
+# CONFIG_SERIAL_8250_DETECT_IRQ is not set
+CONFIG_SERIAL_8250_RSA=y
+
+#
+# Non-8250 serial port support
+#
+CONFIG_SERIAL_MAX3100=m
+# CONFIG_SERIAL_MAX3107 is not set
+# CONFIG_SERIAL_MFD_HSU is not set
+CONFIG_SERIAL_CORE=y
+CONFIG_SERIAL_CORE_CONSOLE=y
+CONFIG_SERIAL_JSM=m
+# CONFIG_SERIAL_TIMBERDALE is not set
+# CONFIG_SERIAL_ALTERA_JTAGUART is not set
+# CONFIG_SERIAL_ALTERA_UART is not set
+# CONFIG_SERIAL_IFX6X60 is not set
+# CONFIG_SERIAL_PCH_UART is not set
+# CONFIG_SERIAL_XILINX_PS_UART is not set
+CONFIG_IPMI_HANDLER=m
+# CONFIG_IPMI_PANIC_EVENT is not set
+CONFIG_IPMI_DEVICE_INTERFACE=m
+CONFIG_IPMI_SI=m
+CONFIG_IPMI_WATCHDOG=m
+CONFIG_IPMI_POWEROFF=m
+CONFIG_HW_RANDOM=y
+CONFIG_HW_RANDOM_TIMERIOMEM=y
+CONFIG_HW_RANDOM_INTEL=y
+# CONFIG_HW_RANDOM_AMD is not set
+CONFIG_HW_RANDOM_GEODE=y
+# CONFIG_HW_RANDOM_VIA is not set
+CONFIG_NVRAM=m
+CONFIG_R3964=m
+CONFIG_APPLICOM=m
+# CONFIG_SONYPI is not set
+# CONFIG_MWAVE is not set
+# CONFIG_PC8736x_GPIO is not set
+# CONFIG_NSC_GPIO is not set
+CONFIG_RAW_DRIVER=m
+CONFIG_MAX_RAW_DEVS=256
+CONFIG_HPET=y
+CONFIG_HPET_MMAP=y
+CONFIG_HANGCHECK_TIMER=m
+# CONFIG_TCG_TPM is not set
+CONFIG_TELCLOCK=m
+CONFIG_DEVPORT=y
+# CONFIG_RAMOOPS is not set
+CONFIG_I2C=y
+CONFIG_I2C_BOARDINFO=y
+CONFIG_I2C_COMPAT=y
+CONFIG_I2C_CHARDEV=m
+# CONFIG_I2C_MUX is not set
+CONFIG_I2C_HELPER_AUTO=y
+CONFIG_I2C_ALGOBIT=m
+
+#
+# I2C Hardware Bus support
+#
+
+#
+# PC SMBus host controller drivers
+#
+# CONFIG_I2C_ALI1535 is not set
+# CONFIG_I2C_ALI1563 is not set
+# CONFIG_I2C_ALI15X3 is not set
+# CONFIG_I2C_AMD756 is not set
+# CONFIG_I2C_AMD8111 is not set
+# CONFIG_I2C_I801 is not set
+CONFIG_I2C_ISCH=y
+# CONFIG_I2C_PIIX4 is not set
+# CONFIG_I2C_NFORCE2 is not set
+# CONFIG_I2C_SIS5595 is not set
+# CONFIG_I2C_SIS630 is not set
+# CONFIG_I2C_SIS96X is not set
+# CONFIG_I2C_VIA is not set
+# CONFIG_I2C_VIAPRO is not set
+
+#
+# ACPI drivers
+#
+CONFIG_I2C_SCMI=m
+
+#
+# I2C system bus drivers (mostly embedded / system-on-chip)
+#
+# CONFIG_I2C_DESIGNWARE_PCI is not set
+# CONFIG_I2C_GPIO is not set
+# CONFIG_I2C_INTEL_MID is not set
+# CONFIG_I2C_OCORES is not set
+# CONFIG_I2C_PCA_PLATFORM is not set
+# CONFIG_I2C_PXA_PCI is not set
+# CONFIG_I2C_SIMTEC is not set
+# CONFIG_I2C_XILINX is not set
+# CONFIG_I2C_EG20T is not set
+
+#
+# External I2C/SMBus adapter drivers
+#
+# CONFIG_I2C_DIOLAN_U2C is not set
+# CONFIG_I2C_PARPORT_LIGHT is not set
+# CONFIG_I2C_TAOS_EVM is not set
+# CONFIG_I2C_TINY_USB is not set
+
+#
+# Other I2C/SMBus bus drivers
+#
+# CONFIG_I2C_STUB is not set
+# CONFIG_SCx200_ACB is not set
+# CONFIG_I2C_DEBUG_CORE is not set
+# CONFIG_I2C_DEBUG_ALGO is not set
+# CONFIG_I2C_DEBUG_BUS is not set
+CONFIG_SPI=y
+# CONFIG_SPI_DEBUG is not set
+CONFIG_SPI_MASTER=y
+
+#
+# SPI Master Controller Drivers
+#
+# CONFIG_SPI_ALTERA is not set
+CONFIG_SPI_BITBANG=m
+# CONFIG_SPI_GPIO is not set
+# CONFIG_SPI_OC_TINY is not set
+# CONFIG_SPI_PXA2XX is not set
+# CONFIG_SPI_PXA2XX_PCI is not set
+# CONFIG_SPI_TOPCLIFF_PCH is not set
+# CONFIG_SPI_XILINX is not set
+# CONFIG_SPI_DESIGNWARE is not set
+
+#
+# SPI Protocol Masters
+#
+# CONFIG_SPI_SPIDEV is not set
+CONFIG_SPI_TLE62X0=m
+
+#
+# PPS support
+#
+CONFIG_PPS=m
+# CONFIG_PPS_DEBUG is not set
+
+#
+# PPS clients support
+#
+# CONFIG_PPS_CLIENT_KTIMER is not set
+# CONFIG_PPS_CLIENT_LDISC is not set
+# CONFIG_PPS_CLIENT_GPIO is not set
+
+#
+# PPS generators support
+#
+
+#
+# PTP clock support
+#
+# CONFIG_PTP_1588_CLOCK is not set
+CONFIG_ARCH_WANT_OPTIONAL_GPIOLIB=y
+CONFIG_GPIOLIB=y
+# CONFIG_DEBUG_GPIO is not set
+# CONFIG_GPIO_SYSFS is not set
+
+#
+# Memory mapped GPIO drivers:
+#
+# CONFIG_GPIO_GENERIC_PLATFORM is not set
+# CONFIG_GPIO_IT8761E is not set
+# CONFIG_GPIO_SCH is not set
+# CONFIG_GPIO_VX855 is not set
+
+#
+# I2C GPIO expanders:
+#
+# CONFIG_GPIO_MAX7300 is not set
+# CONFIG_GPIO_MAX732X is not set
+# CONFIG_GPIO_PCA953X is not set
+# CONFIG_GPIO_PCF857X is not set
+# CONFIG_GPIO_SX150X is not set
+# CONFIG_GPIO_ADP5588 is not set
+
+#
+# PCI GPIO expanders:
+#
+# CONFIG_GPIO_LANGWELL is not set
+# CONFIG_GPIO_PCH is not set
+# CONFIG_GPIO_ML_IOH is not set
+# CONFIG_GPIO_RDC321X is not set
+
+#
+# SPI GPIO expanders:
+#
+# CONFIG_GPIO_MAX7301 is not set
+# CONFIG_GPIO_MCP23S08 is not set
+# CONFIG_GPIO_MC33880 is not set
+# CONFIG_GPIO_74X164 is not set
+
+#
+# AC97 GPIO expanders:
+#
+
+#
+# MODULbus GPIO expanders:
+#
+# CONFIG_W1 is not set
+CONFIG_POWER_SUPPLY=y
+# CONFIG_POWER_SUPPLY_DEBUG is not set
+CONFIG_PDA_POWER=m
+# CONFIG_TEST_POWER is not set
+# CONFIG_BATTERY_DS2780 is not set
+CONFIG_BATTERY_DS2782=m
+# CONFIG_BATTERY_BQ20Z75 is not set
+CONFIG_BATTERY_BQ27x00=m
+CONFIG_BATTERY_BQ27X00_I2C=y
+CONFIG_BATTERY_BQ27X00_PLATFORM=y
+CONFIG_BATTERY_MAX17040=m
+# CONFIG_BATTERY_MAX17042 is not set
+CONFIG_CHARGER_PCF50633=m
+# CONFIG_CHARGER_MAX8903 is not set
+# CONFIG_CHARGER_GPIO is not set
+CONFIG_HWMON=y
+CONFIG_HWMON_VID=m
+# CONFIG_HWMON_DEBUG_CHIP is not set
+
+#
+# Native drivers
+#
+CONFIG_SENSORS_ABITUGURU=m
+CONFIG_SENSORS_ABITUGURU3=m
+# CONFIG_SENSORS_AD7314 is not set
+CONFIG_SENSORS_AD7414=m
+CONFIG_SENSORS_AD7418=m
+CONFIG_SENSORS_ADCXX=m
+CONFIG_SENSORS_ADM1021=m
+CONFIG_SENSORS_ADM1025=m
+CONFIG_SENSORS_ADM1026=m
+CONFIG_SENSORS_ADM1029=m
+CONFIG_SENSORS_ADM1031=m
+CONFIG_SENSORS_ADM9240=m
+# CONFIG_SENSORS_ADT7411 is not set
+CONFIG_SENSORS_ADT7462=m
+CONFIG_SENSORS_ADT7470=m
+CONFIG_SENSORS_ADT7475=m
+# CONFIG_SENSORS_ASC7621 is not set
+CONFIG_SENSORS_K8TEMP=m
+CONFIG_SENSORS_K10TEMP=m
+# CONFIG_SENSORS_FAM15H_POWER is not set
+CONFIG_SENSORS_ASB100=m
+CONFIG_SENSORS_ATXP1=m
+# CONFIG_SENSORS_DS620 is not set
+CONFIG_SENSORS_DS1621=m
+CONFIG_SENSORS_I5K_AMB=m
+CONFIG_SENSORS_F71805F=m
+CONFIG_SENSORS_F71882FG=m
+CONFIG_SENSORS_F75375S=m
+CONFIG_SENSORS_FSCHMD=m
+CONFIG_SENSORS_G760A=m
+CONFIG_SENSORS_GL518SM=m
+CONFIG_SENSORS_GL520SM=m
+# CONFIG_SENSORS_GPIO_FAN is not set
+CONFIG_SENSORS_CORETEMP=m
+CONFIG_SENSORS_IBMAEM=m
+CONFIG_SENSORS_IBMPEX=m
+CONFIG_SENSORS_IT87=m
+# CONFIG_SENSORS_JC42 is not set
+# CONFIG_SENSORS_LINEAGE is not set
+CONFIG_SENSORS_LM63=m
+CONFIG_SENSORS_LM70=m
+# CONFIG_SENSORS_LM73 is not set
+CONFIG_SENSORS_LM75=m
+CONFIG_SENSORS_LM77=m
+CONFIG_SENSORS_LM78=m
+CONFIG_SENSORS_LM80=m
+CONFIG_SENSORS_LM83=m
+CONFIG_SENSORS_LM85=m
+CONFIG_SENSORS_LM87=m
+CONFIG_SENSORS_LM90=m
+CONFIG_SENSORS_LM92=m
+CONFIG_SENSORS_LM93=m
+# CONFIG_SENSORS_LTC4151 is not set
+CONFIG_SENSORS_LTC4215=m
+CONFIG_SENSORS_LTC4245=m
+# CONFIG_SENSORS_LTC4261 is not set
+CONFIG_SENSORS_LM95241=m
+# CONFIG_SENSORS_LM95245 is not set
+CONFIG_SENSORS_MAX1111=m
+# CONFIG_SENSORS_MAX16065 is not set
+CONFIG_SENSORS_MAX1619=m
+# CONFIG_SENSORS_MAX1668 is not set
+# CONFIG_SENSORS_MAX6639 is not set
+# CONFIG_SENSORS_MAX6642 is not set
+CONFIG_SENSORS_MAX6650=m
+# CONFIG_SENSORS_NTC_THERMISTOR is not set
+CONFIG_SENSORS_PC87360=m
+CONFIG_SENSORS_PC87427=m
+CONFIG_SENSORS_PCF8591=m
+# CONFIG_PMBUS is not set
+# CONFIG_SENSORS_SHT15 is not set
+# CONFIG_SENSORS_SHT21 is not set
+CONFIG_SENSORS_SIS5595=m
+# CONFIG_SENSORS_SMM665 is not set
+CONFIG_SENSORS_DME1737=m
+# CONFIG_SENSORS_EMC1403 is not set
+# CONFIG_SENSORS_EMC2103 is not set
+# CONFIG_SENSORS_EMC6W201 is not set
+CONFIG_SENSORS_SMSC47M1=m
+CONFIG_SENSORS_SMSC47M192=m
+CONFIG_SENSORS_SMSC47B397=m
+# CONFIG_SENSORS_SCH56XX_COMMON is not set
+# CONFIG_SENSORS_SCH5627 is not set
+# CONFIG_SENSORS_SCH5636 is not set
+# CONFIG_SENSORS_ADS1015 is not set
+CONFIG_SENSORS_ADS7828=m
+# CONFIG_SENSORS_ADS7871 is not set
+# CONFIG_SENSORS_AMC6821 is not set
+CONFIG_SENSORS_THMC50=m
+# CONFIG_SENSORS_TMP102 is not set
+CONFIG_SENSORS_TMP401=m
+CONFIG_SENSORS_TMP421=m
+CONFIG_SENSORS_VIA_CPUTEMP=m
+CONFIG_SENSORS_VIA686A=m
+CONFIG_SENSORS_VT1211=m
+CONFIG_SENSORS_VT8231=m
+CONFIG_SENSORS_W83781D=m
+CONFIG_SENSORS_W83791D=m
+CONFIG_SENSORS_W83792D=m
+CONFIG_SENSORS_W83793=m
+# CONFIG_SENSORS_W83795 is not set
+CONFIG_SENSORS_W83L785TS=m
+CONFIG_SENSORS_W83L786NG=m
+CONFIG_SENSORS_W83627HF=m
+CONFIG_SENSORS_W83627EHF=m
+CONFIG_SENSORS_APPLESMC=m
+
+#
+# ACPI drivers
+#
+# CONFIG_SENSORS_ACPI_POWER is not set
+CONFIG_SENSORS_ATK0110=m
+CONFIG_THERMAL=y
+CONFIG_THERMAL_HWMON=y
+CONFIG_WATCHDOG=y
+# CONFIG_WATCHDOG_CORE is not set
+# CONFIG_WATCHDOG_NOWAYOUT is not set
+
+#
+# Watchdog Device Drivers
+#
+CONFIG_SOFT_WATCHDOG=m
+CONFIG_ACQUIRE_WDT=m
+CONFIG_ADVANTECH_WDT=m
+CONFIG_ALIM1535_WDT=m
+CONFIG_ALIM7101_WDT=m
+CONFIG_F71808E_WDT=m
+# CONFIG_SP5100_TCO is not set
+CONFIG_SC520_WDT=m
+CONFIG_SBC_FITPC2_WATCHDOG=m
+CONFIG_EUROTECH_WDT=m
+CONFIG_IB700_WDT=m
+CONFIG_IBMASR=m
+CONFIG_WAFER_WDT=m
+CONFIG_I6300ESB_WDT=m
+CONFIG_ITCO_WDT=m
+CONFIG_ITCO_VENDOR_SUPPORT=y
+CONFIG_IT8712F_WDT=m
+CONFIG_IT87_WDT=m
+CONFIG_HP_WATCHDOG=m
+CONFIG_HPWDT_NMI_DECODING=y
+CONFIG_SC1200_WDT=m
+CONFIG_PC87413_WDT=m
+# CONFIG_NV_TCO is not set
+CONFIG_60XX_WDT=m
+CONFIG_SBC8360_WDT=m
+# CONFIG_SBC7240_WDT is not set
+CONFIG_CPU5_WDT=m
+CONFIG_SMSC_SCH311X_WDT=m
+CONFIG_SMSC37B787_WDT=m
+CONFIG_W83627HF_WDT=m
+CONFIG_W83697HF_WDT=m
+CONFIG_W83697UG_WDT=m
+CONFIG_W83877F_WDT=m
+CONFIG_W83977F_WDT=m
+CONFIG_MACHZ_WDT=m
+CONFIG_SBC_EPX_C3_WATCHDOG=m
+
+#
+# PCI-based Watchdog Cards
+#
+CONFIG_PCIPCWATCHDOG=m
+CONFIG_WDTPCI=m
+
+#
+# USB-based Watchdog Cards
+#
+CONFIG_USBPCWATCHDOG=m
+CONFIG_SSB_POSSIBLE=y
+
+#
+# Sonics Silicon Backplane
+#
+CONFIG_SSB=m
+CONFIG_SSB_SPROM=y
+CONFIG_SSB_PCIHOST_POSSIBLE=y
+CONFIG_SSB_PCIHOST=y
+# CONFIG_SSB_B43_PCI_BRIDGE is not set
+CONFIG_SSB_SDIOHOST_POSSIBLE=y
+CONFIG_SSB_SDIOHOST=y
+# CONFIG_SSB_DEBUG is not set
+CONFIG_SSB_DRIVER_PCICORE_POSSIBLE=y
+CONFIG_SSB_DRIVER_PCICORE=y
+CONFIG_BCMA_POSSIBLE=y
+
+#
+# Broadcom specific AMBA
+#
+# CONFIG_BCMA is not set
+
+#
+# Multifunction device drivers
+#
+CONFIG_MFD_CORE=y
+# CONFIG_MFD_88PM860X is not set
+CONFIG_MFD_SM501=m
+# CONFIG_MFD_SM501_GPIO is not set
+CONFIG_HTC_PASIC3=m
+# CONFIG_HTC_I2CPLD is not set
+# CONFIG_TPS6105X is not set
+# CONFIG_TPS65010 is not set
+# CONFIG_TPS6507X is not set
+# CONFIG_MFD_TPS6586X is not set
+# CONFIG_MFD_TPS65910 is not set
+# CONFIG_MFD_TPS65912_I2C is not set
+# CONFIG_MFD_TPS65912_SPI is not set
+# CONFIG_TWL4030_CORE is not set
+# CONFIG_MFD_STMPE is not set
+# CONFIG_MFD_TC3589X is not set
+# CONFIG_MFD_TMIO is not set
+# CONFIG_PMIC_DA903X is not set
+# CONFIG_PMIC_ADP5520 is not set
+# CONFIG_MFD_MAX8925 is not set
+# CONFIG_MFD_MAX8997 is not set
+# CONFIG_MFD_MAX8998 is not set
+CONFIG_MFD_WM8400=m
+# CONFIG_MFD_WM831X_I2C is not set
+# CONFIG_MFD_WM831X_SPI is not set
+# CONFIG_MFD_WM8350_I2C is not set
+# CONFIG_MFD_WM8994 is not set
+CONFIG_MFD_PCF50633=m
+CONFIG_PCF50633_ADC=m
+CONFIG_PCF50633_GPIO=m
+# CONFIG_MFD_MC13XXX is not set
+# CONFIG_ABX500_CORE is not set
+# CONFIG_EZX_PCAP is not set
+# CONFIG_MFD_CS5535 is not set
+# CONFIG_MFD_TIMBERDALE is not set
+CONFIG_LPC_SCH=y
+# CONFIG_MFD_RDC321X is not set
+# CONFIG_MFD_JANZ_CMODIO is not set
+# CONFIG_MFD_VX855 is not set
+# CONFIG_MFD_WL1273_CORE is not set
+# CONFIG_MFD_AAT2870_CORE is not set
+CONFIG_REGULATOR=y
+# CONFIG_REGULATOR_DEBUG is not set
+# CONFIG_REGULATOR_DUMMY is not set
+CONFIG_REGULATOR_FIXED_VOLTAGE=m
+# CONFIG_REGULATOR_VIRTUAL_CONSUMER is not set
+CONFIG_REGULATOR_USERSPACE_CONSUMER=m
+# CONFIG_REGULATOR_GPIO is not set
+CONFIG_REGULATOR_BQ24022=m
+CONFIG_REGULATOR_MAX1586=m
+# CONFIG_REGULATOR_MAX8649 is not set
+# CONFIG_REGULATOR_MAX8660 is not set
+# CONFIG_REGULATOR_MAX8952 is not set
+CONFIG_REGULATOR_WM8400=m
+CONFIG_REGULATOR_PCF50633=m
+CONFIG_REGULATOR_LP3971=m
+# CONFIG_REGULATOR_LP3972 is not set
+CONFIG_REGULATOR_TPS65023=m
+CONFIG_REGULATOR_TPS6507X=m
+# CONFIG_REGULATOR_ISL6271A is not set
+# CONFIG_REGULATOR_AD5398 is not set
+# CONFIG_REGULATOR_TPS6524X is not set
+CONFIG_MEDIA_SUPPORT=y
+
+#
+# Multimedia core support
+#
+# CONFIG_MEDIA_CONTROLLER is not set
+CONFIG_VIDEO_DEV=y
+CONFIG_VIDEO_V4L2_COMMON=y
+# CONFIG_DVB_CORE is not set
+CONFIG_VIDEO_MEDIA=y
+
+#
+# Multimedia drivers
+#
+CONFIG_VIDEO_SAA7146=m
+CONFIG_VIDEO_SAA7146_VV=m
+CONFIG_RC_CORE=m
+CONFIG_LIRC=m
+CONFIG_RC_MAP=m
+CONFIG_IR_NEC_DECODER=m
+CONFIG_IR_RC5_DECODER=m
+CONFIG_IR_RC6_DECODER=m
+CONFIG_IR_JVC_DECODER=m
+CONFIG_IR_SONY_DECODER=m
+CONFIG_IR_RC5_SZ_DECODER=m
+CONFIG_IR_MCE_KBD_DECODER=m
+CONFIG_IR_LIRC_CODEC=m
+# CONFIG_RC_ATI_REMOTE is not set
+# CONFIG_IR_ENE is not set
+# CONFIG_IR_IMON is not set
+# CONFIG_IR_MCEUSB is not set
+# CONFIG_IR_ITE_CIR is not set
+# CONFIG_IR_FINTEK is not set
+# CONFIG_IR_NUVOTON is not set
+# CONFIG_IR_REDRAT3 is not set
+# CONFIG_IR_STREAMZAP is not set
+# CONFIG_IR_WINBOND_CIR is not set
+# CONFIG_RC_LOOPBACK is not set
+CONFIG_MEDIA_ATTACH=y
+CONFIG_MEDIA_TUNER=y
+# CONFIG_MEDIA_TUNER_CUSTOMISE is not set
+CONFIG_MEDIA_TUNER_SIMPLE=y
+CONFIG_MEDIA_TUNER_TDA8290=y
+CONFIG_MEDIA_TUNER_TDA827X=y
+CONFIG_MEDIA_TUNER_TDA18271=y
+CONFIG_MEDIA_TUNER_TDA9887=y
+CONFIG_MEDIA_TUNER_TEA5761=y
+CONFIG_MEDIA_TUNER_TEA5767=y
+CONFIG_MEDIA_TUNER_MT20XX=y
+CONFIG_MEDIA_TUNER_XC2028=y
+CONFIG_MEDIA_TUNER_XC5000=y
+CONFIG_MEDIA_TUNER_XC4000=y
+CONFIG_MEDIA_TUNER_MC44S803=y
+CONFIG_VIDEO_V4L2=y
+CONFIG_VIDEOBUF_GEN=m
+CONFIG_VIDEOBUF_DMA_SG=m
+CONFIG_VIDEOBUF_VMALLOC=m
+CONFIG_VIDEO_BTCX=m
+CONFIG_VIDEO_TVEEPROM=m
+CONFIG_VIDEO_TUNER=m
+CONFIG_VIDEOBUF2_CORE=m
+CONFIG_VIDEOBUF2_MEMOPS=m
+CONFIG_VIDEOBUF2_DMA_CONTIG=m
+CONFIG_VIDEOBUF2_VMALLOC=m
+CONFIG_VIDEO_CAPTURE_DRIVERS=y
+# CONFIG_VIDEO_ADV_DEBUG is not set
+# CONFIG_VIDEO_FIXED_MINOR_RANGES is not set
+CONFIG_VIDEO_HELPER_CHIPS_AUTO=y
+CONFIG_VIDEO_IR_I2C=m
+
+#
+# Audio decoders, processors and mixers
+#
+CONFIG_VIDEO_TVAUDIO=m
+CONFIG_VIDEO_TDA7432=m
+CONFIG_VIDEO_TDA9840=m
+CONFIG_VIDEO_TEA6415C=m
+CONFIG_VIDEO_TEA6420=m
+CONFIG_VIDEO_MSP3400=m
+CONFIG_VIDEO_CS53L32A=m
+CONFIG_VIDEO_WM8775=m
+CONFIG_VIDEO_WM8739=m
+CONFIG_VIDEO_VP27SMPX=m
+
+#
+# RDS decoders
+#
+CONFIG_VIDEO_SAA6588=m
+
+#
+# Video decoders
+#
+CONFIG_VIDEO_BT819=m
+CONFIG_VIDEO_BT856=m
+CONFIG_VIDEO_BT866=m
+CONFIG_VIDEO_KS0127=m
+CONFIG_VIDEO_SAA7110=m
+CONFIG_VIDEO_SAA711X=m
+CONFIG_VIDEO_TVP5150=m
+CONFIG_VIDEO_VPX3220=m
+
+#
+# Video and audio decoders
+#
+CONFIG_VIDEO_SAA717X=m
+CONFIG_VIDEO_CX25840=m
+
+#
+# MPEG video encoders
+#
+CONFIG_VIDEO_CX2341X=m
+
+#
+# Video encoders
+#
+CONFIG_VIDEO_SAA7127=m
+CONFIG_VIDEO_SAA7185=m
+CONFIG_VIDEO_ADV7170=m
+CONFIG_VIDEO_ADV7175=m
+
+#
+# Camera sensor devices
+#
+CONFIG_VIDEO_OV7670=m
+CONFIG_VIDEO_MT9V011=m
+
+#
+# Flash devices
+#
+
+#
+# Video improvement chips
+#
+CONFIG_VIDEO_UPD64031A=m
+CONFIG_VIDEO_UPD64083=m
+
+#
+# Miscelaneous helper chips
+#
+CONFIG_VIDEO_M52790=m
+CONFIG_VIDEO_VIVI=m
+CONFIG_VIDEO_BT848=m
+CONFIG_VIDEO_CPIA2=m
+CONFIG_VIDEO_ZORAN=m
+CONFIG_VIDEO_ZORAN_DC30=m
+CONFIG_VIDEO_ZORAN_ZR36060=m
+CONFIG_VIDEO_ZORAN_BUZ=m
+CONFIG_VIDEO_ZORAN_DC10=m
+CONFIG_VIDEO_ZORAN_LML33=m
+CONFIG_VIDEO_ZORAN_LML33R10=m
+CONFIG_VIDEO_ZORAN_AVS6EYES=m
+CONFIG_VIDEO_SAA7134=m
+CONFIG_VIDEO_SAA7134_RC=y
+CONFIG_VIDEO_MXB=m
+CONFIG_VIDEO_HEXIUM_ORION=m
+CONFIG_VIDEO_HEXIUM_GEMINI=m
+# CONFIG_VIDEO_TIMBERDALE is not set
+CONFIG_VIDEO_CX88=m
+CONFIG_VIDEO_CX88_BLACKBIRD=m
+CONFIG_VIDEO_CX88_MPEG=m
+CONFIG_VIDEO_IVTV=m
+CONFIG_VIDEO_FB_IVTV=m
+CONFIG_VIDEO_CAFE_CCIC=m
+CONFIG_SOC_CAMERA=m
+# CONFIG_SOC_CAMERA_IMX074 is not set
+CONFIG_SOC_CAMERA_MT9M001=m
+CONFIG_SOC_CAMERA_MT9M111=m
+CONFIG_SOC_CAMERA_MT9T031=m
+# CONFIG_SOC_CAMERA_MT9T112 is not set
+CONFIG_SOC_CAMERA_MT9V022=m
+# CONFIG_SOC_CAMERA_RJ54N1 is not set
+CONFIG_SOC_CAMERA_TW9910=m
+CONFIG_SOC_CAMERA_PLATFORM=m
+# CONFIG_SOC_CAMERA_OV2640 is not set
+# CONFIG_SOC_CAMERA_OV5642 is not set
+# CONFIG_SOC_CAMERA_OV6650 is not set
+CONFIG_SOC_CAMERA_OV772X=m
+# CONFIG_SOC_CAMERA_OV9640 is not set
+# CONFIG_SOC_CAMERA_OV9740 is not set
+CONFIG_V4L_USB_DRIVERS=y
+CONFIG_USB_VIDEO_CLASS=y
+CONFIG_USB_VIDEO_CLASS_INPUT_EVDEV=y
+CONFIG_USB_GSPCA=m
+CONFIG_USB_M5602=m
+CONFIG_USB_STV06XX=m
+CONFIG_USB_GL860=m
+# CONFIG_USB_GSPCA_BENQ is not set
+CONFIG_USB_GSPCA_CONEX=m
+# CONFIG_USB_GSPCA_CPIA1 is not set
+CONFIG_USB_GSPCA_ETOMS=m
+CONFIG_USB_GSPCA_FINEPIX=m
+CONFIG_USB_GSPCA_JEILINJ=m
+# CONFIG_USB_GSPCA_KINECT is not set
+# CONFIG_USB_GSPCA_KONICA is not set
+CONFIG_USB_GSPCA_MARS=m
+CONFIG_USB_GSPCA_MR97310A=m
+# CONFIG_USB_GSPCA_NW80X is not set
+CONFIG_USB_GSPCA_OV519=m
+CONFIG_USB_GSPCA_OV534=m
+# CONFIG_USB_GSPCA_OV534_9 is not set
+CONFIG_USB_GSPCA_PAC207=m
+# CONFIG_USB_GSPCA_PAC7302 is not set
+CONFIG_USB_GSPCA_PAC7311=m
+# CONFIG_USB_GSPCA_SE401 is not set
+# CONFIG_USB_GSPCA_SN9C2028 is not set
+CONFIG_USB_GSPCA_SN9C20X=m
+CONFIG_USB_GSPCA_SONIXB=m
+CONFIG_USB_GSPCA_SONIXJ=m
+CONFIG_USB_GSPCA_SPCA500=m
+CONFIG_USB_GSPCA_SPCA501=m
+CONFIG_USB_GSPCA_SPCA505=m
+CONFIG_USB_GSPCA_SPCA506=m
+CONFIG_USB_GSPCA_SPCA508=m
+CONFIG_USB_GSPCA_SPCA561=m
+# CONFIG_USB_GSPCA_SPCA1528 is not set
+CONFIG_USB_GSPCA_SQ905=m
+CONFIG_USB_GSPCA_SQ905C=m
+# CONFIG_USB_GSPCA_SQ930X is not set
+CONFIG_USB_GSPCA_STK014=m
+# CONFIG_USB_GSPCA_STV0680 is not set
+CONFIG_USB_GSPCA_SUNPLUS=m
+CONFIG_USB_GSPCA_T613=m
+# CONFIG_USB_GSPCA_TOPRO is not set
+CONFIG_USB_GSPCA_TV8532=m
+CONFIG_USB_GSPCA_VC032X=m
+# CONFIG_USB_GSPCA_VICAM is not set
+# CONFIG_USB_GSPCA_XIRLINK_CIT is not set
+CONFIG_USB_GSPCA_ZC3XX=m
+CONFIG_VIDEO_PVRUSB2=m
+CONFIG_VIDEO_PVRUSB2_SYSFS=y
+# CONFIG_VIDEO_PVRUSB2_DEBUGIFC is not set
+CONFIG_VIDEO_HDPVR=m
+CONFIG_VIDEO_EM28XX=m
+CONFIG_VIDEO_EM28XX_RC=y
+CONFIG_VIDEO_CX231XX=m
+CONFIG_VIDEO_CX231XX_RC=y
+# CONFIG_VIDEO_TM6000 is not set
+CONFIG_VIDEO_USBVISION=m
+CONFIG_USB_ET61X251=m
+CONFIG_USB_SN9C102=m
+CONFIG_USB_PWC=m
+# CONFIG_USB_PWC_DEBUG is not set
+CONFIG_USB_PWC_INPUT_EVDEV=y
+CONFIG_USB_ZR364XX=m
+CONFIG_USB_STKWEBCAM=m
+CONFIG_USB_S2255=m
+# CONFIG_V4L_MEM2MEM_DRIVERS is not set
+# CONFIG_RADIO_ADAPTERS is not set
+
+#
+# Graphics support
+#
+# CONFIG_AGP is not set
+CONFIG_VGA_ARB=y
+CONFIG_VGA_ARB_MAX_GPUS=16
+# CONFIG_VGA_SWITCHEROO is not set
+# CONFIG_DRM is not set
+# CONFIG_STUB_POULSBO is not set
+CONFIG_VGASTATE=m
+CONFIG_VIDEO_OUTPUT_CONTROL=y
+CONFIG_FB=y
+CONFIG_FIRMWARE_EDID=y
+# CONFIG_FB_DDC is not set
+CONFIG_FB_BOOT_VESA_SUPPORT=y
+CONFIG_FB_CFB_FILLRECT=y
+CONFIG_FB_CFB_COPYAREA=y
+CONFIG_FB_CFB_IMAGEBLIT=y
+# CONFIG_FB_CFB_REV_PIXELS_IN_BYTE is not set
+CONFIG_FB_SYS_FILLRECT=m
+CONFIG_FB_SYS_COPYAREA=m
+CONFIG_FB_SYS_IMAGEBLIT=m
+# CONFIG_FB_FOREIGN_ENDIAN is not set
+CONFIG_FB_SYS_FOPS=m
+# CONFIG_FB_WMT_GE_ROPS is not set
+# CONFIG_FB_SVGALIB is not set
+# CONFIG_FB_MACMODES is not set
+# CONFIG_FB_BACKLIGHT is not set
+CONFIG_FB_MODE_HELPERS=y
+CONFIG_FB_TILEBLITTING=y
+
+#
+# Frame buffer hardware drivers
+#
+# CONFIG_FB_CIRRUS is not set
+# CONFIG_FB_PM2 is not set
+# CONFIG_FB_CYBER2000 is not set
+# CONFIG_FB_ARC is not set
+# CONFIG_FB_ASILIANT is not set
+# CONFIG_FB_IMSTT is not set
+CONFIG_FB_VGA16=m
+# CONFIG_FB_UVESA is not set
+CONFIG_FB_VESA=y
+# CONFIG_FB_N411 is not set
+# CONFIG_FB_HGA is not set
+# CONFIG_FB_S1D13XXX is not set
+# CONFIG_FB_NVIDIA is not set
+# CONFIG_FB_RIVA is not set
+CONFIG_FB_LE80578=m
+CONFIG_FB_CARILLO_RANCH=m
+CONFIG_FB_MATROX=m
+CONFIG_FB_MATROX_MILLENIUM=y
+CONFIG_FB_MATROX_MYSTIQUE=y
+CONFIG_FB_MATROX_G=y
+# CONFIG_FB_MATROX_I2C is not set
+# CONFIG_FB_RADEON is not set
+# CONFIG_FB_ATY128 is not set
+# CONFIG_FB_ATY is not set
+# CONFIG_FB_S3 is not set
+# CONFIG_FB_SAVAGE is not set
+# CONFIG_FB_SIS is not set
+# CONFIG_FB_VIA is not set
+# CONFIG_FB_NEOMAGIC is not set
+# CONFIG_FB_KYRO is not set
+# CONFIG_FB_3DFX is not set
+# CONFIG_FB_VOODOO1 is not set
+# CONFIG_FB_VT8623 is not set
+# CONFIG_FB_TRIDENT is not set
+# CONFIG_FB_ARK is not set
+# CONFIG_FB_PM3 is not set
+# CONFIG_FB_CARMINE is not set
+# CONFIG_FB_GEODE is not set
+# CONFIG_FB_TMIO is not set
+# CONFIG_FB_SM501 is not set
+# CONFIG_FB_SMSCUFX is not set
+# CONFIG_FB_UDL is not set
+CONFIG_FB_VIRTUAL=m
+# CONFIG_FB_METRONOME is not set
+# CONFIG_FB_MB862XX is not set
+# CONFIG_FB_BROADSHEET is not set
+CONFIG_BACKLIGHT_LCD_SUPPORT=y
+# CONFIG_LCD_CLASS_DEVICE is not set
+CONFIG_BACKLIGHT_CLASS_DEVICE=y
+# CONFIG_BACKLIGHT_GENERIC is not set
+CONFIG_BACKLIGHT_PROGEAR=m
+# CONFIG_BACKLIGHT_APPLE is not set
+# CONFIG_BACKLIGHT_SAHARA is not set
+# CONFIG_BACKLIGHT_ADP8860 is not set
+# CONFIG_BACKLIGHT_ADP8870 is not set
+# CONFIG_BACKLIGHT_PCF50633 is not set
+
+#
+# Display device support
+#
+CONFIG_DISPLAY_SUPPORT=m
+
+#
+# Display hardware drivers
+#
+
+#
+# Console display driver support
+#
+CONFIG_VGA_CONSOLE=y
+# CONFIG_VGACON_SOFT_SCROLLBACK is not set
+CONFIG_DUMMY_CONSOLE=y
+CONFIG_FRAMEBUFFER_CONSOLE=y
+CONFIG_FRAMEBUFFER_CONSOLE_DETECT_PRIMARY=y
+CONFIG_FRAMEBUFFER_CONSOLE_ROTATION=y
+# CONFIG_FONTS is not set
+CONFIG_FONT_8x8=y
+CONFIG_FONT_8x16=y
+# CONFIG_LOGO is not set
+# CONFIG_SOUND is not set
+CONFIG_HID_SUPPORT=y
+CONFIG_HID=y
+CONFIG_HIDRAW=y
+
+#
+# USB Input Devices
+#
+CONFIG_USB_HID=y
+CONFIG_HID_PID=y
+CONFIG_USB_HIDDEV=y
+
+#
+# Special HID drivers
+#
+CONFIG_HID_A4TECH=y
+# CONFIG_HID_ACRUX is not set
+CONFIG_HID_APPLE=y
+CONFIG_HID_BELKIN=y
+CONFIG_HID_CHERRY=y
+CONFIG_HID_CHICONY=y
+CONFIG_HID_CYPRESS=y
+# CONFIG_HID_DRAGONRISE is not set
+# CONFIG_HID_EMS_FF is not set
+CONFIG_HID_EZKEY=y
+# CONFIG_HID_HOLTEK is not set
+# CONFIG_HID_KEYTOUCH is not set
+CONFIG_HID_KYE=y
+# CONFIG_HID_UCLOGIC is not set
+# CONFIG_HID_WALTOP is not set
+# CONFIG_HID_GYRATION is not set
+# CONFIG_HID_TWINHAN is not set
+CONFIG_HID_KENSINGTON=y
+# CONFIG_HID_LCPOWER is not set
+CONFIG_HID_LOGITECH=y
+CONFIG_HID_LOGITECH_DJ=m
+CONFIG_LOGITECH_FF=y
+CONFIG_LOGIRUMBLEPAD2_FF=y
+# CONFIG_LOGIG940_FF is not set
+CONFIG_LOGIWHEELS_FF=y
+CONFIG_HID_MICROSOFT=y
+CONFIG_HID_MONTEREY=y
+# CONFIG_HID_MULTITOUCH is not set
+# CONFIG_HID_NTRIG is not set
+# CONFIG_HID_ORTEK is not set
+# CONFIG_HID_PANTHERLORD is not set
+# CONFIG_HID_PETALYNX is not set
+# CONFIG_HID_PICOLCD is not set
+# CONFIG_HID_PRIMAX is not set
+# CONFIG_HID_QUANTA is not set
+# CONFIG_HID_ROCCAT is not set
+# CONFIG_HID_SAMSUNG is not set
+CONFIG_HID_SONY=m
+# CONFIG_HID_SPEEDLINK is not set
+# CONFIG_HID_SUNPLUS is not set
+# CONFIG_HID_GREENASIA is not set
+# CONFIG_HID_SMARTJOYPLUS is not set
+# CONFIG_HID_TOPSEED is not set
+CONFIG_HID_THRUSTMASTER=m
+CONFIG_THRUSTMASTER_FF=y
+# CONFIG_HID_ZEROPLUS is not set
+# CONFIG_HID_ZYDACRON is not set
+CONFIG_USB_SUPPORT=y
+CONFIG_USB_COMMON=y
+CONFIG_USB_ARCH_HAS_HCD=y
+CONFIG_USB_ARCH_HAS_OHCI=y
+CONFIG_USB_ARCH_HAS_EHCI=y
+CONFIG_USB_ARCH_HAS_XHCI=y
+CONFIG_USB=y
+# CONFIG_USB_DEBUG is not set
+CONFIG_USB_ANNOUNCE_NEW_DEVICES=y
+
+#
+# Miscellaneous USB options
+#
+CONFIG_USB_DEVICEFS=y
+# CONFIG_USB_DEVICE_CLASS is not set
+CONFIG_USB_DYNAMIC_MINORS=y
+CONFIG_USB_SUSPEND=y
+# CONFIG_USB_OTG is not set
+# CONFIG_USB_DWC3 is not set
+CONFIG_USB_MON=y
+# CONFIG_USB_WUSB is not set
+# CONFIG_USB_WUSB_CBAF is not set
+
+#
+# USB Host Controller Drivers
+#
+# CONFIG_USB_C67X00_HCD is not set
+# CONFIG_USB_XHCI_HCD is not set
+CONFIG_USB_EHCI_HCD=y
+CONFIG_USB_EHCI_ROOT_HUB_TT=y
+CONFIG_USB_EHCI_TT_NEWSCHED=y
+# CONFIG_USB_OXU210HP_HCD is not set
+# CONFIG_USB_ISP116X_HCD is not set
+# CONFIG_USB_ISP1760_HCD is not set
+# CONFIG_USB_ISP1362_HCD is not set
+# CONFIG_USB_OHCI_HCD is not set
+CONFIG_USB_UHCI_HCD=y
+# CONFIG_USB_SL811_HCD is not set
+# CONFIG_USB_R8A66597_HCD is not set
+# CONFIG_USB_WHCI_HCD is not set
+# CONFIG_USB_HWA_HCD is not set
+
+#
+# USB Device Class drivers
+#
+CONFIG_USB_ACM=y
+# CONFIG_USB_PRINTER is not set
+# CONFIG_USB_WDM is not set
+CONFIG_USB_TMC=y
+
+#
+# NOTE: USB_STORAGE depends on SCSI but BLK_DEV_SD may
+#
+
+#
+# also be needed; see USB_STORAGE Help for more info
+#
+CONFIG_USB_STORAGE=y
+# CONFIG_USB_STORAGE_DEBUG is not set
+# CONFIG_USB_STORAGE_REALTEK is not set
+CONFIG_USB_STORAGE_DATAFAB=m
+CONFIG_USB_STORAGE_FREECOM=m
+CONFIG_USB_STORAGE_ISD200=m
+CONFIG_USB_STORAGE_USBAT=m
+CONFIG_USB_STORAGE_SDDR09=m
+CONFIG_USB_STORAGE_SDDR55=m
+CONFIG_USB_STORAGE_JUMPSHOT=m
+CONFIG_USB_STORAGE_ALAUDA=m
+CONFIG_USB_STORAGE_ONETOUCH=m
+CONFIG_USB_STORAGE_KARMA=m
+CONFIG_USB_STORAGE_CYPRESS_ATACB=m
+# CONFIG_USB_STORAGE_ENE_UB6250 is not set
+# CONFIG_USB_UAS is not set
+# CONFIG_USB_LIBUSUAL is not set
+
+#
+# USB Imaging devices
+#
+# CONFIG_USB_MDC800 is not set
+# CONFIG_USB_MICROTEK is not set
+
+#
+# USB port drivers
+#
+CONFIG_USB_SERIAL=m
+CONFIG_USB_EZUSB=y
+CONFIG_USB_SERIAL_GENERIC=y
+CONFIG_USB_SERIAL_AIRCABLE=m
+CONFIG_USB_SERIAL_ARK3116=m
+CONFIG_USB_SERIAL_BELKIN=m
+CONFIG_USB_SERIAL_CH341=m
+CONFIG_USB_SERIAL_WHITEHEAT=m
+CONFIG_USB_SERIAL_DIGI_ACCELEPORT=m
+CONFIG_USB_SERIAL_CP210X=m
+CONFIG_USB_SERIAL_CYPRESS_M8=m
+CONFIG_USB_SERIAL_EMPEG=m
+CONFIG_USB_SERIAL_FTDI_SIO=m
+CONFIG_USB_SERIAL_FUNSOFT=m
+CONFIG_USB_SERIAL_VISOR=m
+CONFIG_USB_SERIAL_IPAQ=m
+CONFIG_USB_SERIAL_IR=m
+CONFIG_USB_SERIAL_EDGEPORT=m
+CONFIG_USB_SERIAL_EDGEPORT_TI=m
+CONFIG_USB_SERIAL_GARMIN=m
+CONFIG_USB_SERIAL_IPW=m
+CONFIG_USB_SERIAL_IUU=m
+CONFIG_USB_SERIAL_KEYSPAN_PDA=m
+CONFIG_USB_SERIAL_KEYSPAN=m
+CONFIG_USB_SERIAL_KLSI=m
+CONFIG_USB_SERIAL_KOBIL_SCT=m
+CONFIG_USB_SERIAL_MCT_U232=m
+CONFIG_USB_SERIAL_MOS7720=m
+CONFIG_USB_SERIAL_MOS7840=m
+CONFIG_USB_SERIAL_MOTOROLA=m
+CONFIG_USB_SERIAL_NAVMAN=m
+CONFIG_USB_SERIAL_PL2303=m
+CONFIG_USB_SERIAL_OTI6858=m
+# CONFIG_USB_SERIAL_QCAUX is not set
+CONFIG_USB_SERIAL_QUALCOMM=m
+CONFIG_USB_SERIAL_SPCP8X5=m
+CONFIG_USB_SERIAL_HP4X=m
+CONFIG_USB_SERIAL_SAFE=m
+# CONFIG_USB_SERIAL_SAFE_PADDED is not set
+CONFIG_USB_SERIAL_SIEMENS_MPI=m
+CONFIG_USB_SERIAL_SIERRAWIRELESS=m
+CONFIG_USB_SERIAL_SYMBOL=m
+CONFIG_USB_SERIAL_TI=m
+CONFIG_USB_SERIAL_CYBERJACK=m
+CONFIG_USB_SERIAL_XIRCOM=m
+CONFIG_USB_SERIAL_WWAN=m
+CONFIG_USB_SERIAL_OPTION=m
+CONFIG_USB_SERIAL_OMNINET=m
+CONFIG_USB_SERIAL_OPTICON=m
+# CONFIG_USB_SERIAL_VIVOPAY_SERIAL is not set
+# CONFIG_USB_SERIAL_ZIO is not set
+# CONFIG_USB_SERIAL_SSU100 is not set
+CONFIG_USB_SERIAL_DEBUG=m
+
+#
+# USB Miscellaneous drivers
+#
+# CONFIG_USB_EMI62 is not set
+# CONFIG_USB_EMI26 is not set
+# CONFIG_USB_ADUTUX is not set
+# CONFIG_USB_SEVSEG is not set
+# CONFIG_USB_RIO500 is not set
+CONFIG_USB_LEGOTOWER=m
+# CONFIG_USB_LCD is not set
+# CONFIG_USB_LED is not set
+CONFIG_USB_CYPRESS_CY7C63=m
+# CONFIG_USB_CYTHERM is not set
+# CONFIG_USB_IDMOUSE is not set
+# CONFIG_USB_FTDI_ELAN is not set
+# CONFIG_USB_APPLEDISPLAY is not set
+# CONFIG_USB_SISUSBVGA is not set
+CONFIG_USB_LD=m
+CONFIG_USB_TRANCEVIBRATOR=m
+# CONFIG_USB_IOWARRIOR is not set
+CONFIG_USB_TEST=m
+# CONFIG_USB_ISIGHTFW is not set
+# CONFIG_USB_YUREX is not set
+# CONFIG_USB_ATM is not set
+# CONFIG_USB_GADGET is not set
+
+#
+# OTG and related infrastructure
+#
+# CONFIG_USB_GPIO_VBUS is not set
+# CONFIG_NOP_USB_XCEIV is not set
+# CONFIG_UWB is not set
+CONFIG_MMC=y
+# CONFIG_MMC_DEBUG is not set
+# CONFIG_MMC_UNSAFE_RESUME is not set
+# CONFIG_MMC_CLKGATE is not set
+
+#
+# MMC/SD/SDIO Card Drivers
+#
+CONFIG_MMC_BLOCK=m
+CONFIG_MMC_BLOCK_MINORS=8
+CONFIG_MMC_BLOCK_BOUNCE=y
+# CONFIG_SDIO_UART is not set
+# CONFIG_MMC_TEST is not set
+
+#
+# MMC/SD/SDIO Host Controller Drivers
+#
+CONFIG_MMC_SDHCI=y
+CONFIG_MMC_SDHCI_PCI=y
+# CONFIG_MMC_RICOH_MMC is not set
+CONFIG_MMC_SDHCI_PLTFM=m
+# CONFIG_MMC_WBSD is not set
+CONFIG_MMC_TIFM_SD=m
+CONFIG_MMC_CB710=m
+CONFIG_MMC_VIA_SDMMC=m
+# CONFIG_MMC_VUB300 is not set
+# CONFIG_MMC_USHC is not set
+# CONFIG_MEMSTICK is not set
+CONFIG_NEW_LEDS=y
+CONFIG_LEDS_CLASS=y
+
+#
+# LED drivers
+#
+# CONFIG_LEDS_LM3530 is not set
+CONFIG_LEDS_PCA9532=m
+# CONFIG_LEDS_PCA9532_GPIO is not set
+# CONFIG_LEDS_GPIO is not set
+CONFIG_LEDS_LP3944=m
+# CONFIG_LEDS_LP5521 is not set
+# CONFIG_LEDS_LP5523 is not set
+CONFIG_LEDS_CLEVO_MAIL=m
+CONFIG_LEDS_PCA955X=m
+CONFIG_LEDS_DAC124S085=m
+# CONFIG_LEDS_REGULATOR is not set
+CONFIG_LEDS_BD2802=m
+# CONFIG_LEDS_INTEL_SS4200 is not set
+# CONFIG_LEDS_LT3593 is not set
+# CONFIG_LEDS_DELL_NETBOOKS is not set
+CONFIG_LEDS_TRIGGERS=y
+
+#
+# LED Triggers
+#
+CONFIG_LEDS_TRIGGER_TIMER=m
+CONFIG_LEDS_TRIGGER_HEARTBEAT=m
+CONFIG_LEDS_TRIGGER_BACKLIGHT=m
+# CONFIG_LEDS_TRIGGER_GPIO is not set
+CONFIG_LEDS_TRIGGER_DEFAULT_ON=m
+
+#
+# iptables trigger is under Netfilter config (LED target)
+#
+CONFIG_ACCESSIBILITY=y
+CONFIG_A11Y_BRAILLE_CONSOLE=y
+# CONFIG_INFINIBAND is not set
+CONFIG_EDAC=y
+
+#
+# Reporting subsystems
+#
+# CONFIG_EDAC_DEBUG is not set
+CONFIG_EDAC_MM_EDAC=m
+# CONFIG_EDAC_AMD76X is not set
+# CONFIG_EDAC_E7XXX is not set
+CONFIG_EDAC_E752X=m
+# CONFIG_EDAC_I82875P is not set
+CONFIG_EDAC_I82975X=m
+CONFIG_EDAC_I3000=m
+CONFIG_EDAC_I3200=m
+CONFIG_EDAC_X38=m
+CONFIG_EDAC_I5400=m
+# CONFIG_EDAC_I7CORE is not set
+# CONFIG_EDAC_I82860 is not set
+# CONFIG_EDAC_R82600 is not set
+CONFIG_EDAC_I5000=m
+CONFIG_EDAC_I5100=m
+# CONFIG_EDAC_I7300 is not set
+CONFIG_RTC_LIB=y
+CONFIG_RTC_CLASS=y
+CONFIG_RTC_HCTOSYS=y
+CONFIG_RTC_HCTOSYS_DEVICE="rtc0"
+# CONFIG_RTC_DEBUG is not set
+
+#
+# RTC interfaces
+#
+CONFIG_RTC_INTF_SYSFS=y
+CONFIG_RTC_INTF_PROC=y
+CONFIG_RTC_INTF_DEV=y
+# CONFIG_RTC_INTF_DEV_UIE_EMUL is not set
+# CONFIG_RTC_DRV_TEST is not set
+
+#
+# I2C RTC drivers
+#
+CONFIG_RTC_DRV_DS1307=m
+CONFIG_RTC_DRV_DS1374=m
+CONFIG_RTC_DRV_DS1672=m
+# CONFIG_RTC_DRV_DS3232 is not set
+CONFIG_RTC_DRV_MAX6900=m
+CONFIG_RTC_DRV_RS5C372=m
+CONFIG_RTC_DRV_ISL1208=m
+# CONFIG_RTC_DRV_ISL12022 is not set
+CONFIG_RTC_DRV_X1205=m
+CONFIG_RTC_DRV_PCF8563=m
+CONFIG_RTC_DRV_PCF8583=m
+CONFIG_RTC_DRV_M41T80=m
+# CONFIG_RTC_DRV_M41T80_WDT is not set
+# CONFIG_RTC_DRV_BQ32K is not set
+CONFIG_RTC_DRV_S35390A=m
+CONFIG_RTC_DRV_FM3130=m
+CONFIG_RTC_DRV_RX8581=m
+CONFIG_RTC_DRV_RX8025=m
+# CONFIG_RTC_DRV_EM3027 is not set
+# CONFIG_RTC_DRV_RV3029C2 is not set
+
+#
+# SPI RTC drivers
+#
+# CONFIG_RTC_DRV_M41T93 is not set
+CONFIG_RTC_DRV_M41T94=m
+CONFIG_RTC_DRV_DS1305=m
+CONFIG_RTC_DRV_DS1390=m
+CONFIG_RTC_DRV_MAX6902=m
+CONFIG_RTC_DRV_R9701=m
+CONFIG_RTC_DRV_RS5C348=m
+CONFIG_RTC_DRV_DS3234=m
+CONFIG_RTC_DRV_PCF2123=m
+
+#
+# Platform RTC drivers
+#
+CONFIG_RTC_DRV_CMOS=y
+CONFIG_RTC_DRV_DS1286=m
+CONFIG_RTC_DRV_DS1511=m
+CONFIG_RTC_DRV_DS1553=m
+CONFIG_RTC_DRV_DS1742=m
+CONFIG_RTC_DRV_STK17TA8=m
+CONFIG_RTC_DRV_M48T86=m
+CONFIG_RTC_DRV_M48T35=m
+CONFIG_RTC_DRV_M48T59=m
+# CONFIG_RTC_DRV_MSM6242 is not set
+CONFIG_RTC_DRV_BQ4802=m
+# CONFIG_RTC_DRV_RP5C01 is not set
+CONFIG_RTC_DRV_V3020=m
+CONFIG_RTC_DRV_PCF50633=m
+
+#
+# on-CPU RTC drivers
+#
+CONFIG_DMADEVICES=y
+# CONFIG_DMADEVICES_DEBUG is not set
+
+#
+# DMA Devices
+#
+# CONFIG_INTEL_MID_DMAC is not set
+CONFIG_INTEL_IOATDMA=m
+# CONFIG_TIMB_DMA is not set
+# CONFIG_PCH_DMA is not set
+CONFIG_DMA_ENGINE=y
+
+#
+# DMA Clients
+#
+CONFIG_NET_DMA=y
+CONFIG_ASYNC_TX_DMA=y
+# CONFIG_DMATEST is not set
+CONFIG_DCA=m
+# CONFIG_AUXDISPLAY is not set
+CONFIG_UIO=m
+# CONFIG_UIO_CIF is not set
+CONFIG_UIO_PDRV=m
+CONFIG_UIO_PDRV_GENIRQ=m
+# CONFIG_UIO_AEC is not set
+# CONFIG_UIO_SERCOS3 is not set
+# CONFIG_UIO_PCI_GENERIC is not set
+# CONFIG_UIO_NETX is not set
+
+#
+# Virtio drivers
+#
+# CONFIG_VIRTIO_PCI is not set
+# CONFIG_VIRTIO_BALLOON is not set
+# CONFIG_VIRTIO_MMIO is not set
+CONFIG_STAGING=y
+# CONFIG_ET131X is not set
+# CONFIG_SLICOSS is not set
+# CONFIG_USBIP_CORE is not set
+# CONFIG_ECHO is not set
+# CONFIG_COMEDI is not set
+# CONFIG_ASUS_OLED is not set
+# CONFIG_RTS_PSTOR is not set
+# CONFIG_RTS5139 is not set
+# CONFIG_TRANZPORT is not set
+# CONFIG_POHMELFS is not set
+# CONFIG_IDE_PHISON is not set
+# CONFIG_USB_SERIAL_QUATECH2 is not set
+# CONFIG_USB_SERIAL_QUATECH_USB2 is not set
+# CONFIG_VME_BUS is not set
+# CONFIG_DX_SEP is not set
+# CONFIG_IIO is not set
+# CONFIG_XVMALLOC is not set
+# CONFIG_ZRAM is not set
+# CONFIG_FB_SM7XX is not set
+# CONFIG_CRYSTALHD is not set
+# CONFIG_FB_XGI is not set
+# CONFIG_ACPI_QUICKSTART is not set
+# CONFIG_USB_ENESTORAGE is not set
+# CONFIG_BCM_WIMAX is not set
+# CONFIG_FT1000 is not set
+
+#
+# Speakup console speech
+#
+CONFIG_SPEAKUP=m
+CONFIG_SPEAKUP_SYNTH_ACNTSA=m
+CONFIG_SPEAKUP_SYNTH_ACNTPC=m
+CONFIG_SPEAKUP_SYNTH_APOLLO=m
+CONFIG_SPEAKUP_SYNTH_AUDPTR=m
+CONFIG_SPEAKUP_SYNTH_BNS=m
+CONFIG_SPEAKUP_SYNTH_DECTLK=m
+CONFIG_SPEAKUP_SYNTH_DECEXT=m
+# CONFIG_SPEAKUP_SYNTH_DECPC is not set
+CONFIG_SPEAKUP_SYNTH_DTLK=m
+CONFIG_SPEAKUP_SYNTH_KEYPC=m
+CONFIG_SPEAKUP_SYNTH_LTLK=m
+CONFIG_SPEAKUP_SYNTH_SOFT=m
+CONFIG_SPEAKUP_SYNTH_SPKOUT=m
+CONFIG_SPEAKUP_SYNTH_TXPRT=m
+CONFIG_SPEAKUP_SYNTH_DUMMY=m
+# CONFIG_TOUCHSCREEN_CLEARPAD_TM1217 is not set
+# CONFIG_TOUCHSCREEN_SYNAPTICS_I2C_RMI4 is not set
+# CONFIG_STAGING_MEDIA is not set
+CONFIG_X86_PLATFORM_DEVICES=y
+# CONFIG_ACER_WMI is not set
+# CONFIG_ACERHDF is not set
+# CONFIG_ASUS_LAPTOP is not set
+# CONFIG_DELL_LAPTOP is not set
+# CONFIG_DELL_WMI is not set
+# CONFIG_DELL_WMI_AIO is not set
+# CONFIG_FUJITSU_LAPTOP is not set
+# CONFIG_TC1100_WMI is not set
+# CONFIG_HP_ACCEL is not set
+# CONFIG_HP_WMI is not set
+# CONFIG_PANASONIC_LAPTOP is not set
+# CONFIG_THINKPAD_ACPI is not set
+# CONFIG_SENSORS_HDAPS is not set
+# CONFIG_INTEL_MENLOW is not set
+# CONFIG_EEEPC_LAPTOP is not set
+# CONFIG_ASUS_WMI is not set
+CONFIG_ACPI_WMI=m
+# CONFIG_MSI_WMI is not set
+# CONFIG_ACPI_ASUS is not set
+# CONFIG_TOPSTAR_LAPTOP is not set
+# CONFIG_ACPI_TOSHIBA is not set
+# CONFIG_TOSHIBA_BT_RFKILL is not set
+# CONFIG_ACPI_CMPC is not set
+# CONFIG_INTEL_IPS is not set
+# CONFIG_IBM_RTL is not set
+# CONFIG_XO15_EBOOK is not set
+# CONFIG_MXM_WMI is not set
+# CONFIG_SAMSUNG_Q10 is not set
+
+#
+# Hardware Spinlock drivers
+#
+CONFIG_CLKSRC_I8253=y
+CONFIG_CLKEVT_I8253=y
+CONFIG_I8253_LOCK=y
+CONFIG_CLKBLD_I8253=y
+CONFIG_IOMMU_SUPPORT=y
+# CONFIG_INTEL_IOMMU is not set
+# CONFIG_VIRT_DRIVERS is not set
+# CONFIG_HYPERV is not set
+# CONFIG_PM_DEVFREQ is not set
+
+#
+# Firmware Drivers
+#
+CONFIG_EDD=m
+# CONFIG_EDD_OFF is not set
+CONFIG_FIRMWARE_MEMMAP=y
+CONFIG_DELL_RBU=m
+CONFIG_DCDBAS=m
+CONFIG_DMIID=y
+# CONFIG_DMI_SYSFS is not set
+CONFIG_ISCSI_IBFT_FIND=y
+CONFIG_ISCSI_IBFT=y
+# CONFIG_SIGMA is not set
+# CONFIG_GOOGLE_FIRMWARE is not set
+
+#
+# File systems
+#
+CONFIG_EXT2_FS=y
+CONFIG_EXT2_FS_XATTR=y
+CONFIG_EXT2_FS_POSIX_ACL=y
+CONFIG_EXT2_FS_SECURITY=y
+# CONFIG_EXT2_FS_XIP is not set
+CONFIG_EXT3_FS=y
+CONFIG_EXT3_DEFAULTS_TO_ORDERED=y
+CONFIG_EXT3_FS_XATTR=y
+CONFIG_EXT3_FS_POSIX_ACL=y
+CONFIG_EXT3_FS_SECURITY=y
+# CONFIG_EXT4_FS is not set
+CONFIG_JBD=y
+# CONFIG_JBD_DEBUG is not set
+CONFIG_FS_MBCACHE=y
+# CONFIG_REISERFS_FS is not set
+# CONFIG_JFS_FS is not set
+CONFIG_XFS_FS=y
+CONFIG_XFS_QUOTA=y
+CONFIG_XFS_POSIX_ACL=y
+CONFIG_XFS_RT=y
+# CONFIG_XFS_DEBUG is not set
+# CONFIG_GFS2_FS is not set
+# CONFIG_OCFS2_FS is not set
+# CONFIG_BTRFS_FS is not set
+# CONFIG_NILFS2_FS is not set
+CONFIG_FS_POSIX_ACL=y
+CONFIG_EXPORTFS=y
+CONFIG_FILE_LOCKING=y
+CONFIG_FSNOTIFY=y
+CONFIG_DNOTIFY=y
+CONFIG_INOTIFY_USER=y
+# CONFIG_FANOTIFY is not set
+CONFIG_QUOTA=y
+CONFIG_QUOTA_NETLINK_INTERFACE=y
+CONFIG_PRINT_QUOTA_WARNING=y
+# CONFIG_QUOTA_DEBUG is not set
+CONFIG_QUOTA_TREE=m
+CONFIG_QFMT_V1=m
+CONFIG_QFMT_V2=m
+CONFIG_QUOTACTL=y
+CONFIG_AUTOFS4_FS=m
+CONFIG_FUSE_FS=m
+CONFIG_CUSE=m
+CONFIG_GENERIC_ACL=y
+
+#
+# Caches
+#
+# CONFIG_FSCACHE is not set
+
+#
+# CD-ROM/DVD Filesystems
+#
+CONFIG_ISO9660_FS=y
+CONFIG_JOLIET=y
+CONFIG_ZISOFS=y
+CONFIG_UDF_FS=m
+CONFIG_UDF_NLS=y
+
+#
+# DOS/FAT/NT Filesystems
+#
+CONFIG_FAT_FS=m
+CONFIG_MSDOS_FS=m
+CONFIG_VFAT_FS=m
+CONFIG_FAT_DEFAULT_CODEPAGE=437
+CONFIG_FAT_DEFAULT_IOCHARSET="utf8"
+# CONFIG_NTFS_FS is not set
+
+#
+# Pseudo filesystems
+#
+CONFIG_PROC_FS=y
+CONFIG_PROC_KCORE=y
+CONFIG_PROC_SYSCTL=y
+CONFIG_PROC_PAGE_MONITOR=y
+CONFIG_SYSFS=y
+CONFIG_TMPFS=y
+CONFIG_TMPFS_POSIX_ACL=y
+CONFIG_TMPFS_XATTR=y
+# CONFIG_HUGETLBFS is not set
+# CONFIG_HUGETLB_PAGE is not set
+CONFIG_CONFIGFS_FS=m
+# CONFIG_MISC_FILESYSTEMS is not set
+# CONFIG_NETWORK_FILESYSTEMS is not set
+
+#
+# Partition Types
+#
+CONFIG_PARTITION_ADVANCED=y
+# CONFIG_ACORN_PARTITION is not set
+# CONFIG_OSF_PARTITION is not set
+# CONFIG_AMIGA_PARTITION is not set
+# CONFIG_ATARI_PARTITION is not set
+# CONFIG_MAC_PARTITION is not set
+CONFIG_MSDOS_PARTITION=y
+CONFIG_BSD_DISKLABEL=y
+CONFIG_MINIX_SUBPARTITION=y
+CONFIG_SOLARIS_X86_PARTITION=y
+CONFIG_UNIXWARE_DISKLABEL=y
+CONFIG_LDM_PARTITION=y
+# CONFIG_LDM_DEBUG is not set
+# CONFIG_SGI_PARTITION is not set
+# CONFIG_ULTRIX_PARTITION is not set
+# CONFIG_SUN_PARTITION is not set
+# CONFIG_KARMA_PARTITION is not set
+# CONFIG_EFI_PARTITION is not set
+# CONFIG_SYSV68_PARTITION is not set
+CONFIG_NLS=y
+CONFIG_NLS_DEFAULT="utf8"
+CONFIG_NLS_CODEPAGE_437=y
+# CONFIG_NLS_CODEPAGE_737 is not set
+# CONFIG_NLS_CODEPAGE_775 is not set
+# CONFIG_NLS_CODEPAGE_850 is not set
+# CONFIG_NLS_CODEPAGE_852 is not set
+# CONFIG_NLS_CODEPAGE_855 is not set
+# CONFIG_NLS_CODEPAGE_857 is not set
+# CONFIG_NLS_CODEPAGE_860 is not set
+# CONFIG_NLS_CODEPAGE_861 is not set
+# CONFIG_NLS_CODEPAGE_862 is not set
+# CONFIG_NLS_CODEPAGE_863 is not set
+# CONFIG_NLS_CODEPAGE_864 is not set
+# CONFIG_NLS_CODEPAGE_865 is not set
+# CONFIG_NLS_CODEPAGE_866 is not set
+# CONFIG_NLS_CODEPAGE_869 is not set
+# CONFIG_NLS_CODEPAGE_936 is not set
+# CONFIG_NLS_CODEPAGE_950 is not set
+# CONFIG_NLS_CODEPAGE_932 is not set
+# CONFIG_NLS_CODEPAGE_949 is not set
+# CONFIG_NLS_CODEPAGE_874 is not set
+# CONFIG_NLS_ISO8859_8 is not set
+# CONFIG_NLS_CODEPAGE_1250 is not set
+# CONFIG_NLS_CODEPAGE_1251 is not set
+CONFIG_NLS_ASCII=y
+# CONFIG_NLS_ISO8859_1 is not set
+# CONFIG_NLS_ISO8859_2 is not set
+# CONFIG_NLS_ISO8859_3 is not set
+# CONFIG_NLS_ISO8859_4 is not set
+# CONFIG_NLS_ISO8859_5 is not set
+# CONFIG_NLS_ISO8859_6 is not set
+# CONFIG_NLS_ISO8859_7 is not set
+# CONFIG_NLS_ISO8859_9 is not set
+# CONFIG_NLS_ISO8859_13 is not set
+# CONFIG_NLS_ISO8859_14 is not set
+# CONFIG_NLS_ISO8859_15 is not set
+# CONFIG_NLS_KOI8_R is not set
+# CONFIG_NLS_KOI8_U is not set
+CONFIG_NLS_UTF8=y
+CONFIG_DLM=m
+CONFIG_DLM_DEBUG=y
+
+#
+# Kernel hacking
+#
+CONFIG_TRACE_IRQFLAGS_SUPPORT=y
+CONFIG_PRINTK_TIME=y
+CONFIG_DEFAULT_MESSAGE_LOGLEVEL=4
+CONFIG_ENABLE_WARN_DEPRECATED=y
+CONFIG_ENABLE_MUST_CHECK=y
+CONFIG_FRAME_WARN=1024
+CONFIG_MAGIC_SYSRQ=y
+# CONFIG_MAGIC_SYSRQ_FORCE_PRINTK is not set
+CONFIG_STRIP_ASM_SYMS=y
+CONFIG_UNUSED_SYMBOLS=y
+CONFIG_DEBUG_FS=y
+# CONFIG_HEADERS_CHECK is not set
+# CONFIG_DEBUG_SECTION_MISMATCH is not set
+CONFIG_DEBUG_KERNEL=y
+# CONFIG_LOCKUP_DETECTOR is not set
+# CONFIG_HARDLOCKUP_DETECTOR is not set
+CONFIG_DETECT_HUNG_TASK=y
+CONFIG_DEFAULT_HUNG_TASK_TIMEOUT=120
+# CONFIG_BOOTPARAM_HUNG_TASK_PANIC is not set
+CONFIG_BOOTPARAM_HUNG_TASK_PANIC_VALUE=0
+CONFIG_SCHED_DEBUG=y
+# CONFIG_SCHEDSTATS is not set
+CONFIG_TIMER_STATS=y
+# CONFIG_DEBUG_OBJECTS is not set
+# CONFIG_DEBUG_SLAB is not set
+# CONFIG_DEBUG_KMEMLEAK is not set
+CONFIG_DEBUG_PREEMPT=y
+# CONFIG_DEBUG_RT_MUTEXES is not set
+# CONFIG_RT_MUTEX_TESTER is not set
+# CONFIG_DEBUG_SPINLOCK is not set
+# CONFIG_DEBUG_MUTEXES is not set
+# CONFIG_DEBUG_LOCK_ALLOC is not set
+# CONFIG_PROVE_LOCKING is not set
+# CONFIG_SPARSE_RCU_POINTER is not set
+# CONFIG_LOCK_STAT is not set
+# CONFIG_DEBUG_ATOMIC_SLEEP is not set
+# CONFIG_DEBUG_LOCKING_API_SELFTESTS is not set
+CONFIG_STACKTRACE=y
+# CONFIG_DEBUG_STACK_USAGE is not set
+# CONFIG_DEBUG_KOBJECT is not set
+# CONFIG_DEBUG_HIGHMEM is not set
+CONFIG_DEBUG_BUGVERBOSE=y
+# CONFIG_DEBUG_INFO is not set
+# CONFIG_DEBUG_VM is not set
+# CONFIG_DEBUG_VIRTUAL is not set
+# CONFIG_DEBUG_WRITECOUNT is not set
+CONFIG_DEBUG_MEMORY_INIT=y
+# CONFIG_DEBUG_LIST is not set
+# CONFIG_TEST_LIST_SORT is not set
+# CONFIG_DEBUG_SG is not set
+# CONFIG_DEBUG_NOTIFIERS is not set
+# CONFIG_DEBUG_CREDENTIALS is not set
+CONFIG_ARCH_WANT_FRAME_POINTERS=y
+# CONFIG_FRAME_POINTER is not set
+# CONFIG_BOOT_PRINTK_DELAY is not set
+# CONFIG_RCU_TORTURE_TEST is not set
+CONFIG_RCU_CPU_STALL_TIMEOUT=60
+CONFIG_RCU_CPU_STALL_VERBOSE=y
+# CONFIG_KPROBES_SANITY_TEST is not set
+# CONFIG_BACKTRACE_SELF_TEST is not set
+# CONFIG_DEBUG_BLOCK_EXT_DEVT is not set
+# CONFIG_DEBUG_FORCE_WEAK_PER_CPU is not set
+# CONFIG_DEBUG_PER_CPU_MAPS is not set
+# CONFIG_LKDTM is not set
+# CONFIG_CPU_NOTIFIER_ERROR_INJECT is not set
+# CONFIG_FAULT_INJECTION is not set
+# CONFIG_LATENCYTOP is not set
+CONFIG_SYSCTL_SYSCALL_CHECK=y
+# CONFIG_DEBUG_PAGEALLOC is not set
+CONFIG_USER_STACKTRACE_SUPPORT=y
+CONFIG_NOP_TRACER=y
+CONFIG_HAVE_FUNCTION_TRACER=y
+CONFIG_HAVE_FUNCTION_GRAPH_TRACER=y
+CONFIG_HAVE_FUNCTION_GRAPH_FP_TEST=y
+CONFIG_HAVE_FUNCTION_TRACE_MCOUNT_TEST=y
+CONFIG_HAVE_DYNAMIC_FTRACE=y
+CONFIG_HAVE_FTRACE_MCOUNT_RECORD=y
+CONFIG_HAVE_SYSCALL_TRACEPOINTS=y
+CONFIG_HAVE_C_RECORDMCOUNT=y
+CONFIG_RING_BUFFER=y
+CONFIG_EVENT_TRACING=y
+CONFIG_EVENT_POWER_TRACING_DEPRECATED=y
+CONFIG_CONTEXT_SWITCH_TRACER=y
+CONFIG_TRACING=y
+CONFIG_GENERIC_TRACER=y
+CONFIG_TRACING_SUPPORT=y
+CONFIG_FTRACE=y
+# CONFIG_FUNCTION_TRACER is not set
+# CONFIG_IRQSOFF_TRACER is not set
+# CONFIG_PREEMPT_TRACER is not set
+# CONFIG_SCHED_TRACER is not set
+# CONFIG_MISSED_TIMER_OFFSETS_HIST is not set
+# CONFIG_FTRACE_SYSCALLS is not set
+CONFIG_BRANCH_PROFILE_NONE=y
+# CONFIG_PROFILE_ANNOTATED_BRANCHES is not set
+# CONFIG_PROFILE_ALL_BRANCHES is not set
+# CONFIG_STACK_TRACER is not set
+CONFIG_BLK_DEV_IO_TRACE=y
+CONFIG_KPROBE_EVENT=y
+# CONFIG_FTRACE_STARTUP_TEST is not set
+# CONFIG_MMIOTRACE is not set
+# CONFIG_RING_BUFFER_BENCHMARK is not set
+# CONFIG_PROVIDE_OHCI1394_DMA_INIT is not set
+# CONFIG_FIREWIRE_OHCI_REMOTE_DMA is not set
+# CONFIG_DYNAMIC_DEBUG is not set
+# CONFIG_DMA_API_DEBUG is not set
+# CONFIG_ATOMIC64_SELFTEST is not set
+# CONFIG_SAMPLES is not set
+CONFIG_HAVE_ARCH_KGDB=y
+# CONFIG_KGDB is not set
+CONFIG_HAVE_ARCH_KMEMCHECK=y
+# CONFIG_KMEMCHECK is not set
+# CONFIG_TEST_KSTRTOX is not set
+CONFIG_STRICT_DEVMEM=y
+CONFIG_X86_VERBOSE_BOOTUP=y
+CONFIG_EARLY_PRINTK=y
+# CONFIG_EARLY_PRINTK_DBGP is not set
+# CONFIG_DEBUG_STACKOVERFLOW is not set
+# CONFIG_X86_PTDUMP is not set
+CONFIG_DEBUG_RODATA=y
+# CONFIG_DEBUG_RODATA_TEST is not set
+# CONFIG_DEBUG_SET_MODULE_RONX is not set
+# CONFIG_DEBUG_NX_TEST is not set
+CONFIG_DOUBLEFAULT=y
+# CONFIG_IOMMU_STRESS is not set
+CONFIG_HAVE_MMIOTRACE_SUPPORT=y
+# CONFIG_X86_DECODER_SELFTEST is not set
+CONFIG_IO_DELAY_TYPE_0X80=0
+CONFIG_IO_DELAY_TYPE_0XED=1
+CONFIG_IO_DELAY_TYPE_UDELAY=2
+CONFIG_IO_DELAY_TYPE_NONE=3
+CONFIG_IO_DELAY_0X80=y
+# CONFIG_IO_DELAY_0XED is not set
+# CONFIG_IO_DELAY_UDELAY is not set
+# CONFIG_IO_DELAY_NONE is not set
+CONFIG_DEFAULT_IO_DELAY_TYPE=0
+# CONFIG_DEBUG_BOOT_PARAMS is not set
+# CONFIG_CPA_DEBUG is not set
+CONFIG_OPTIMIZE_INLINING=y
+# CONFIG_DEBUG_STRICT_USER_COPY_CHECKS is not set
+
+#
+# Security options
+#
+CONFIG_KEYS=y
+# CONFIG_ENCRYPTED_KEYS is not set
+CONFIG_KEYS_DEBUG_PROC_KEYS=y
+# CONFIG_SECURITY_DMESG_RESTRICT is not set
+CONFIG_SECURITY=y
+CONFIG_SECURITYFS=y
+# CONFIG_SECURITY_NETWORK is not set
+# CONFIG_SECURITY_PATH is not set
+# CONFIG_SECURITY_TOMOYO is not set
+# CONFIG_SECURITY_APPARMOR is not set
+# CONFIG_IMA is not set
+# CONFIG_EVM is not set
+CONFIG_DEFAULT_SECURITY_DAC=y
+CONFIG_DEFAULT_SECURITY=""
+CONFIG_ASYNC_TX_DISABLE_PQ_VAL_DMA=y
+CONFIG_ASYNC_TX_DISABLE_XOR_VAL_DMA=y
+CONFIG_CRYPTO=y
+
+#
+# Crypto core or helper
+#
+CONFIG_CRYPTO_ALGAPI=y
+CONFIG_CRYPTO_ALGAPI2=y
+CONFIG_CRYPTO_AEAD=m
+CONFIG_CRYPTO_AEAD2=y
+CONFIG_CRYPTO_BLKCIPHER=m
+CONFIG_CRYPTO_BLKCIPHER2=y
+CONFIG_CRYPTO_HASH=y
+CONFIG_CRYPTO_HASH2=y
+CONFIG_CRYPTO_RNG=m
+CONFIG_CRYPTO_RNG2=y
+CONFIG_CRYPTO_PCOMP=m
+CONFIG_CRYPTO_PCOMP2=y
+CONFIG_CRYPTO_MANAGER=y
+CONFIG_CRYPTO_MANAGER2=y
+# CONFIG_CRYPTO_USER is not set
+CONFIG_CRYPTO_MANAGER_DISABLE_TESTS=y
+CONFIG_CRYPTO_GF128MUL=m
+CONFIG_CRYPTO_NULL=m
+# CONFIG_CRYPTO_PCRYPT is not set
+CONFIG_CRYPTO_WORKQUEUE=y
+# CONFIG_CRYPTO_CRYPTD is not set
+CONFIG_CRYPTO_AUTHENC=m
+CONFIG_CRYPTO_TEST=m
+
+#
+# Authenticated Encryption with Associated Data
+#
+CONFIG_CRYPTO_CCM=m
+CONFIG_CRYPTO_GCM=m
+CONFIG_CRYPTO_SEQIV=m
+
+#
+# Block modes
+#
+CONFIG_CRYPTO_CBC=m
+CONFIG_CRYPTO_CTR=m
+CONFIG_CRYPTO_CTS=m
+CONFIG_CRYPTO_ECB=m
+CONFIG_CRYPTO_LRW=m
+CONFIG_CRYPTO_PCBC=m
+CONFIG_CRYPTO_XTS=m
+
+#
+# Hash modes
+#
+CONFIG_CRYPTO_HMAC=m
+CONFIG_CRYPTO_XCBC=m
+CONFIG_CRYPTO_VMAC=m
+
+#
+# Digest
+#
+CONFIG_CRYPTO_CRC32C=m
+CONFIG_CRYPTO_CRC32C_INTEL=m
+CONFIG_CRYPTO_GHASH=m
+CONFIG_CRYPTO_MD4=m
+CONFIG_CRYPTO_MD5=y
+CONFIG_CRYPTO_MICHAEL_MIC=m
+CONFIG_CRYPTO_RMD128=m
+CONFIG_CRYPTO_RMD160=m
+CONFIG_CRYPTO_RMD256=m
+CONFIG_CRYPTO_RMD320=m
+CONFIG_CRYPTO_SHA1=m
+CONFIG_CRYPTO_SHA256=m
+CONFIG_CRYPTO_SHA512=m
+CONFIG_CRYPTO_TGR192=m
+CONFIG_CRYPTO_WP512=m
+
+#
+# Ciphers
+#
+CONFIG_CRYPTO_AES=m
+# CONFIG_CRYPTO_AES_586 is not set
+# CONFIG_CRYPTO_AES_NI_INTEL is not set
+CONFIG_CRYPTO_ANUBIS=m
+CONFIG_CRYPTO_ARC4=m
+CONFIG_CRYPTO_BLOWFISH=m
+CONFIG_CRYPTO_BLOWFISH_COMMON=m
+CONFIG_CRYPTO_CAMELLIA=m
+CONFIG_CRYPTO_CAST5=m
+CONFIG_CRYPTO_CAST6=m
+CONFIG_CRYPTO_DES=m
+CONFIG_CRYPTO_FCRYPT=m
+CONFIG_CRYPTO_KHAZAD=m
+CONFIG_CRYPTO_SALSA20=m
+# CONFIG_CRYPTO_SALSA20_586 is not set
+CONFIG_CRYPTO_SEED=m
+CONFIG_CRYPTO_SERPENT=m
+CONFIG_CRYPTO_TEA=m
+CONFIG_CRYPTO_TWOFISH=m
+CONFIG_CRYPTO_TWOFISH_COMMON=m
+# CONFIG_CRYPTO_TWOFISH_586 is not set
+
+#
+# Compression
+#
+CONFIG_CRYPTO_DEFLATE=m
+CONFIG_CRYPTO_ZLIB=m
+CONFIG_CRYPTO_LZO=m
+
+#
+# Random Number Generation
+#
+CONFIG_CRYPTO_ANSI_CPRNG=m
+# CONFIG_CRYPTO_USER_API_HASH is not set
+# CONFIG_CRYPTO_USER_API_SKCIPHER is not set
+CONFIG_CRYPTO_HW=y
+CONFIG_CRYPTO_DEV_PADLOCK=m
+CONFIG_CRYPTO_DEV_PADLOCK_AES=m
+CONFIG_CRYPTO_DEV_PADLOCK_SHA=m
+# CONFIG_CRYPTO_DEV_GEODE is not set
+# CONFIG_CRYPTO_DEV_HIFN_795X is not set
+CONFIG_HAVE_KVM=y
+# CONFIG_VIRTUALIZATION is not set
+CONFIG_BINARY_PRINTF=y
+
+#
+# Library routines
+#
+CONFIG_BITREVERSE=y
+CONFIG_GENERIC_FIND_FIRST_BIT=y
+CONFIG_CRC_CCITT=m
+CONFIG_CRC16=m
+CONFIG_CRC_T10DIF=y
+CONFIG_CRC_ITU_T=m
+CONFIG_CRC32=y
+CONFIG_CRC7=m
+CONFIG_LIBCRC32C=m
+# CONFIG_CRC8 is not set
+CONFIG_AUDIT_GENERIC=y
+CONFIG_ZLIB_INFLATE=y
+CONFIG_ZLIB_DEFLATE=m
+CONFIG_LZO_COMPRESS=y
+CONFIG_LZO_DECOMPRESS=y
+CONFIG_XZ_DEC=y
+CONFIG_XZ_DEC_X86=y
+CONFIG_XZ_DEC_POWERPC=y
+CONFIG_XZ_DEC_IA64=y
+CONFIG_XZ_DEC_ARM=y
+CONFIG_XZ_DEC_ARMTHUMB=y
+CONFIG_XZ_DEC_SPARC=y
+CONFIG_XZ_DEC_BCJ=y
+# CONFIG_XZ_DEC_TEST is not set
+CONFIG_DECOMPRESS_GZIP=y
+CONFIG_DECOMPRESS_BZIP2=y
+CONFIG_DECOMPRESS_LZMA=y
+CONFIG_DECOMPRESS_XZ=y
+CONFIG_DECOMPRESS_LZO=y
+CONFIG_REED_SOLOMON=m
+CONFIG_REED_SOLOMON_DEC16=y
+CONFIG_TEXTSEARCH=y
+CONFIG_TEXTSEARCH_KMP=m
+CONFIG_TEXTSEARCH_BM=m
+CONFIG_TEXTSEARCH_FSM=m
+CONFIG_HAS_IOMEM=y
+CONFIG_HAS_IOPORT=y
+CONFIG_HAS_DMA=y
+CONFIG_CHECK_SIGNATURE=y
+CONFIG_CPU_RMAP=y
+CONFIG_NLATTR=y
+CONFIG_AVERAGE=y
+# CONFIG_CORDIC is not set
diff --git a/aos/config/setup_rt_caps.sh b/aos/config/setup_rt_caps.sh
new file mode 100755
index 0000000..11fb1f1
--- /dev/null
+++ b/aos/config/setup_rt_caps.sh
@@ -0,0 +1,5 @@
+#!/bin/bash
+# has to be run as root
+
+setcap 'CAP_IPC_LOCK+pie CAP_SYS_NICE+pie' $0
+
diff --git a/aos/config/starter b/aos/config/starter
new file mode 100755
index 0000000..f82df4b
--- /dev/null
+++ b/aos/config/starter
@@ -0,0 +1,158 @@
+#! /bin/sh
+### BEGIN INIT INFO
+# Provides: starter
+# Required-Start: $remote_fs $syslog sshd $all
+# Required-Stop: $remote_fs $syslog
+# Default-Start: 2 3 4 5
+# Default-Stop: 0 1 6
+# Short-Description: AOS Startup Code
+# Description: Starts up all of the AOS-related things (FRC robot code).
+### END INIT INFO
+# pam_limits
+
+# Author: Spartan Robotics <spartanrobotics.org>
+
+# Do NOT "set -e"
+
+# PATH should only include /usr/* if it runs after the mountnfs.sh script
+PATH=/sbin:/usr/sbin:/bin:/usr/bin
+DESC="FRC robot code"
+NAME=starter
+DAEMON=/home/driver/robot_code/bin/$NAME.sh
+DAEMON_ARGS="/home/driver/robot_code/bin/start_list.txt"
+PIDFILE=/tmp/$NAME.pid
+SCRIPTNAME=/etc/init.d/$NAME
+
+# Exit if the package is not installed
+[ -x "$DAEMON" ] || exit 0
+
+# Read configuration variable file if it is present
+[ -r /etc/default/$NAME ] && . /etc/default/$NAME
+
+# Load the VERBOSE setting and other rcS variables
+. /lib/init/vars.sh
+
+# Define LSB log_* functions.
+# Depend on lsb-base (>= 3.2-14) to ensure that this file is present
+# and status_of_proc is working.
+. /lib/lsb/init-functions
+VERBOSE=yes
+
+#
+# Function that starts the daemon/service
+#
+do_start()
+{
+ # Return
+ # 0 if daemon has been started
+ # 1 if daemon was already running
+ # 2 if daemon could not be started
+ start-stop-daemon --start --quiet --pidfile $PIDFILE --exec $DAEMON --test > /dev/null \
+ || return 1
+ start-stop-daemon --start --quiet --pidfile $PIDFILE --exec $DAEMON -- \
+ $DAEMON_ARGS \
+ || return 2
+ # Add code here, if necessary, that waits for the process to be ready
+ # to handle requests from services started subsequently which depend
+ # on this one. As a last resort, sleep for some time.
+}
+
+#
+# Function that stops the daemon/service
+#
+do_stop()
+{
+ # Return
+ # 0 if daemon has been stopped
+ # 1 if daemon was already stopped
+ # 2 if daemon could not be stopped
+ # other if a failure occurred
+ start-stop-daemon --stop --quiet --retry=INT/10/KILL/5 --pidfile $PIDFILE
+ RETVAL="$?"
+ [ "$RETVAL" = 2 ] && return 2
+ # Wait for children to finish too if this is a daemon that forks
+ # and if the daemon is only ever run from this initscript.
+ # If the above conditions are not satisfied then add some other code
+ # that waits for the process to drop all resources that could be
+ # needed by services started subsequently. A last resort is to
+ # sleep for some time.
+ #start-stop-daemon --stop --quiet --oknodo --retry=INT/10/KILL/5
+ #[ "$?" = 2 ] && return 2
+ sleep 10
+ # Many daemons don't delete their pidfiles when they exit.
+ rm -f $PIDFILE
+ return "$RETVAL"
+}
+
+#
+# Function that sends a SIGHUP to the daemon/service
+#
+do_reload() {
+ #
+ # If the daemon can reload its configuration without
+ # restarting (for example, when it is sent a SIGHUP),
+ # then implement that here.
+ #
+ start-stop-daemon --stop --signal 1 --quiet --pidfile $PIDFILE --name $NAME
+ return 0
+}
+
+case "$1" in
+ start)
+ [ "$VERBOSE" != no ] && log_daemon_msg "Starting $DESC" "$NAME"
+ do_start
+ case "$?" in
+ 0|1) [ "$VERBOSE" != no ] && log_end_msg 0 ;;
+ 2) [ "$VERBOSE" != no ] && log_end_msg 1 ;;
+ esac
+ ;;
+ stop)
+ [ "$VERBOSE" != no ] && log_daemon_msg "Stopping $DESC" "$NAME"
+ do_stop
+ case "$?" in
+ 0|1) [ "$VERBOSE" != no ] && log_end_msg 0 ;;
+ 2) [ "$VERBOSE" != no ] && log_end_msg 1 ;;
+ esac
+ ;;
+ status)
+ status_of_proc "$DAEMON" "$NAME" && exit 0 || exit $?
+ ;;
+ #reload|force-reload)
+ #
+ # If do_reload() is not implemented then leave this commented out
+ # and leave 'force-reload' as an alias for 'restart'.
+ #
+ #log_daemon_msg "Reloading $DESC" "$NAME"
+ #do_reload
+ #log_end_msg $?
+ #;;
+ restart|force-reload)
+ #
+ # If the "reload" option is implemented then remove the
+ # 'force-reload' alias
+ #
+ log_daemon_msg "Restarting $DESC" "$NAME"
+ do_stop
+ case "$?" in
+ 0|1)
+ do_start
+ case "$?" in
+ 0) log_end_msg 0 ;;
+ 1) log_end_msg 1 ;; # Old process is still running
+ *) log_end_msg 1 ;; # Failed to start
+ esac
+ ;;
+ *)
+ # Failed to stop
+ log_end_msg 1
+ ;;
+ esac
+ ;;
+ *)
+ #echo "Usage: $SCRIPTNAME {start|stop|restart|reload|force-reload}" >&2
+ echo "Usage: $SCRIPTNAME {start|stop|status|restart|force-reload}" >&2
+ exit 3
+ ;;
+esac
+
+:
diff --git a/aos/crio/README.txt b/aos/crio/README.txt
new file mode 100644
index 0000000..182b323
--- /dev/null
+++ b/aos/crio/README.txt
@@ -0,0 +1,5 @@
+see ../README.txt for stuff affecting crio and atom code
+
+[NOTES]
+The assumption that sizeof(pointers) == sizeof(int) == sizeof(UINT32) == sizeof(uint32_t) == 4 is all over the crio code. The vxworks apis use UINT32 to pass user-defined arguments, and just passing pointers through those makes the code a lot simpler.
+
diff --git a/aos/crio/Talon.cpp b/aos/crio/Talon.cpp
new file mode 100644
index 0000000..54ef459
--- /dev/null
+++ b/aos/crio/Talon.cpp
@@ -0,0 +1,21 @@
+#include "aos/crio/Talon.h"
+#include "WPILib/DigitalModule.h"
+
+Talon::Talon(UINT32 channel) : SafePWM(channel) {
+ // 255 = 2.5ms, 0 = 0.5ms (or something close to that)
+ // these numbers were determined empirically with real hardware by Brian
+ // on 11/23/12
+ // got 211->210 as first transition that made a speed difference and
+ // 53->54 on the other side
+ // going 2 to each side to make sure we get the full range
+ SetBounds(213, 137, 132, 127, 50);
+ // 1X = every 5.05ms, 2X and 4x are multiples of that
+ SetPeriodMultiplier(kPeriodMultiplier_1X);
+ SetRaw(m_centerPwm);
+}
+
+void Talon::Set(float speed, UINT8 /*syncGroup*/) { SetSpeed(speed); }
+float Talon::Get() { return GetSpeed(); }
+void Talon::Disable() { SetRaw(kPwmDisabled); }
+
+void Talon::PIDWrite(float output) { Set(output); }
diff --git a/aos/crio/Talon.h b/aos/crio/Talon.h
new file mode 100644
index 0000000..c116a4d
--- /dev/null
+++ b/aos/crio/Talon.h
@@ -0,0 +1,21 @@
+#ifndef AOS_CRIO_TALON_H_
+#define AOS_CRIO_TALON_H_
+
+#include "WPILib/SafePWM.h"
+#include "WPILib/SpeedController.h"
+#include "WPILib/PIDOutput.h"
+
+// Used for controlling a Talon speed controller. Non-standard API and
+// namespace so that the likely WPILib version will be drop-in replaceable.
+class Talon : public SafePWM, public SpeedController, public PIDOutput {
+ public:
+ explicit Talon(UINT32 channel);
+
+ virtual void Set(float value, UINT8 syncGroup=0);
+ virtual float Get();
+ virtual void Disable();
+
+ virtual void PIDWrite(float output);
+};
+
+#endif // AOS_CRIO_TALON_H_
diff --git a/aos/crio/aos_ctdt.h b/aos/crio/aos_ctdt.h
new file mode 100644
index 0000000..9292823
--- /dev/null
+++ b/aos/crio/aos_ctdt.h
@@ -0,0 +1,17 @@
+#ifndef AOS_CTDT_H_
+#define AOS_CTDT_H_
+
+// This function will call any function that starts with aos_init_function_*.
+// It will assume that these functions have the signature
+// 'extern "C" aos_init_function_whatever(void);'
+// The aos_ctdt.c/o files are generated at compile time (like ctdt.c/o).
+#ifdef __cplusplus
+extern "C" {
+#endif
+void aos_call_init_functions();
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
diff --git a/aos/crio/bin/netconsole.sh b/aos/crio/bin/netconsole.sh
new file mode 100755
index 0000000..8976400
--- /dev/null
+++ b/aos/crio/bin/netconsole.sh
@@ -0,0 +1,3 @@
+#!/bin/bash
+
+socat UDP4-RECV:6666,reuseaddr!!UDP4-SENDTO:robot:6668 READLINE
diff --git a/aos/crio/controls/ControlsManager.cpp b/aos/crio/controls/ControlsManager.cpp
new file mode 100644
index 0000000..a37ec6f
--- /dev/null
+++ b/aos/crio/controls/ControlsManager.cpp
@@ -0,0 +1,53 @@
+#include <stdio.h>
+#include <stdlib.h>
+
+#include "WPILib/Compressor.h"
+
+#include "aos/aos_core.h"
+#include "aos/crio/controls/ControlsManager.h"
+#include "aos/common/Configuration.h"
+#include "aos/crio/aos_ctdt.h"
+#include "aos/crio/motor_server/CRIOControlLoopRunner.h"
+#include "aos/crio/motor_server/MotorServer.h"
+
+namespace aos {
+namespace crio {
+
+// Everything gets an explicit Start call here before calling all of the init
+// functions because it means that all static variables will be initialized
+// before anything actually starts running. It also means that everything will
+// be initialized before any of the init functions start trying to register
+// themselves etc.
+void ControlsManager::StartCompetition() {
+ printf("aos::ControlsManager::RobotMain\n");
+ (new Compressor(14, 1))->Start();
+
+ logging::Start();
+ LOG(INFO, "logging started\n");
+
+ GetWatchdog().SetEnabled(false);
+ LOG(INFO, "disabled watchdog\n");
+
+ RegisterControlLoops();
+ LOG(INFO, "registered control loops\n");
+
+ // CRIOControlLoopRunner calls part of MotorServer, so MotorServer has to get
+ // initialized first.
+ MotorServer::Start();
+ LOG(INFO, "MotorServer started\n");
+ CRIOControlLoopRunner::Start();
+ LOG(INFO, "cRIO control loops started\n");
+
+ LOG(INFO, "calling init functions\n");
+ aos_call_init_functions();
+ LOG(INFO, "initialized\n");
+
+ // Wait forever so that this task doesn't end to avoid confusing any brittle
+ // FIRST code that might be hiding somewhere.
+ while (true) {
+ select(0, NULL, NULL, NULL, NULL);
+ }
+}
+
+} // namespace crio
+} // namespace aos
diff --git a/aos/crio/controls/ControlsManager.h b/aos/crio/controls/ControlsManager.h
new file mode 100644
index 0000000..986fe02
--- /dev/null
+++ b/aos/crio/controls/ControlsManager.h
@@ -0,0 +1,21 @@
+#include "WPILib/DriverStation.h"
+#include "WPILib/RobotBase.h"
+
+namespace aos {
+namespace crio {
+
+class ControlsManager : public RobotBase {
+ public:
+ // Gets called when it is time to register all the control loops.
+ virtual void RegisterControlLoops() = 0;
+ virtual void StartCompetition();
+ static inline ControlsManager &GetInstance() {
+ return *static_cast<ControlsManager *>(&RobotBase::getInstance());
+ }
+ inline DriverStation *GetDS() {
+ return m_ds;
+ }
+};
+
+} // namespace crio
+} // namespace aos
diff --git a/aos/crio/controls/JoyStickRead.cpp b/aos/crio/controls/JoyStickRead.cpp
new file mode 100644
index 0000000..1f5e4c7
--- /dev/null
+++ b/aos/crio/controls/JoyStickRead.cpp
@@ -0,0 +1,91 @@
+#include "WPILib/Task.h"
+#include "WPILib/Timer.h"
+
+#include "aos/aos_core.h"
+#include "aos/crio/controls/ControlsManager.h"
+#include "aos/common/network/SendSocket.h"
+#include "aos/common/messages/RobotState.q.h"
+
+namespace aos {
+namespace crio {
+
+class JoystickRead {
+ /*virtual void Disabled () {
+ int i = 0;
+ while (IsDisabled()) {
+ printf("Disabled! %d\n", i);
+ Wait(0.1);
+ i++;
+ }
+ printf("Done with disabled. %d\n", i);
+ }
+ virtual void Autonomous () {
+ int j = 0;
+ while (IsAutonomous()) {
+ printf("Autonomous! %d\n", j);
+ Wait(0.1);
+ //if (j > 5) {
+ //i(0);
+ //}
+ j ++;
+ }
+ printf("Done with autonomous. %d\n", j);
+ }
+ virtual void OperatorControl () {
+ int i = 0;
+ while (IsOperatorControl()) {
+ printf("Operator Control! %d\n", i);
+ Wait(0.1);
+ i ++;
+ }
+ printf("Done with operator control. %d\n", i);
+ }*/
+ public:
+ DriverStation *ds;
+ JoystickRead() {}
+ void Run() {
+ SendSocket sock(NetworkPort::kDS,
+ configuration::GetIPAddress(
+ configuration::NetworkDevice::kAtom));
+ FRCCommonControlData data;
+
+ ds = ControlsManager::GetInstance().GetDS();
+
+ while (true) {
+ // I checked, and this is done intelligently in WPILib.
+ ds->WaitForData();
+
+ robot_state.MakeWithBuilder().enabled(ds->IsEnabled())
+ .autonomous(ds->IsAutonomous()).team_id(ds->GetTeamNumber()).Send();
+ LOG(DEBUG, "sending joystick data\n");
+ data.enabled = ds->IsEnabled();
+ data.autonomous = ds->IsAutonomous();
+ data.fmsAttached = ds->IsFMSAttached();
+ SetStick(data.stick0Axes, 1);
+ SetStick(data.stick1Axes, 2);
+ SetStick(data.stick2Axes, 3);
+ SetStick(data.stick3Axes, 4);
+ data.stick0Buttons = ds->GetStickButtons(1);
+ data.stick1Buttons = ds->GetStickButtons(2);
+ data.stick2Buttons = ds->GetStickButtons(3);
+ data.stick3Buttons = ds->GetStickButtons(4);
+ data.teamID = ds->GetTeamNumber();
+ sock.Send(&data, sizeof(data));
+ }
+ }
+ void SetStick(int8_t axes[6], uint32_t stick) {
+ for (int i = 0; i < 6; ++i) {
+ double val = ds->GetStickAxis(stick, i + 1);
+ if (val < 0) {
+ axes[i] = (val * 128.0) + 0.5;
+ } else {
+ axes[i] = (val * 127.0) + 0.5;
+ }
+ }
+ }
+};
+
+} // namespace crio
+} // namespace aos
+
+AOS_RUN_FORK(aos::crio::JoystickRead, "JSR", 100)
diff --git a/aos/crio/crio.gyp b/aos/crio/crio.gyp
new file mode 100644
index 0000000..2d37999
--- /dev/null
+++ b/aos/crio/crio.gyp
@@ -0,0 +1,19 @@
+{
+ 'targets': [
+ {
+ # This test runs on the atom to verify that the cRIO version of the queues
+ # works.
+ 'target_name': 'unsafe_queue_test',
+ 'type': '<(aos_target)',
+ 'sources': [
+ 'queue_test.cc',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(AOS)/common/common.gyp:common',
+ '<(AOS)/common/common.gyp:queue_test_queue',
+ ],
+ },
+ ],
+}
diff --git a/aos/crio/googletest/google_test_server.cc b/aos/crio/googletest/google_test_server.cc
new file mode 100644
index 0000000..46631b5
--- /dev/null
+++ b/aos/crio/googletest/google_test_server.cc
@@ -0,0 +1,45 @@
+#include <stdio.h>
+
+#include "gtest/gtest.h"
+
+extern "C" int run_gtest(char *arg1, char *arg2, char *arg3, char *arg4,
+ char *arg5, char *arg6, char *arg7, char *arg8,
+ char *arg9, char *arg10, char *arg11) {
+ static bool run = false;
+ if (!run) {
+ run = true;
+ } else {
+ printf("error: gtest only supports being run once\n");
+ return -1;
+ }
+
+ char *argv[1 + 11 + 1];
+ // In /tmp in case it wants to write anything relative to "itself".
+ argv[0] = const_cast<char *>("/tmp/aos-crio-googletest-runner");
+ argv[12] = NULL; // the argv passed to main is always NULL-terminated
+ argv[1] = arg1;
+ argv[2] = arg2;
+ argv[3] = arg3;
+ argv[4] = arg4;
+ argv[5] = arg5;
+ argv[6] = arg6;
+ argv[7] = arg7;
+ argv[8] = arg8;
+ argv[9] = arg9;
+ argv[10] = arg10;
+ argv[11] = arg11;
+ int argc = 0;
+ while (argc[argv] != NULL) ++argc;
+
+ testing::GTEST_FLAG(color) = "yes";
+ testing::InitGoogleTest(&argc, argv);
+
+ if (argc > 1) {
+ printf("warning: flags not recognized by gtest passed\n");
+ for (int i = 1; i < argc; ++i) {
+ printf("\t%s\n", argv[i]);
+ }
+ }
+
+ return RUN_ALL_TESTS();
+}
diff --git a/aos/crio/googletest/googletest.gyp b/aos/crio/googletest/googletest.gyp
new file mode 100644
index 0000000..d887ecd
--- /dev/null
+++ b/aos/crio/googletest/googletest.gyp
@@ -0,0 +1,14 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'googletest',
+ 'type': 'static_library',
+ 'sources': [
+ 'google_test_server.cc',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ ],
+ },
+ ],
+}
diff --git a/aos/crio/logging/crio_logging.cpp b/aos/crio/logging/crio_logging.cpp
new file mode 100644
index 0000000..8ebafc0
--- /dev/null
+++ b/aos/crio/logging/crio_logging.cpp
@@ -0,0 +1,110 @@
+#include <string.h>
+
+#include "WPILib/Timer.h"
+#include "WPILib/Task.h"
+
+#include "aos/aos_core.h"
+#include "aos/common/network/SendSocket.h"
+#include "aos/common/Configuration.h"
+#include "aos/common/die.h"
+
+#undef ERROR
+#define DECL_LEVEL(name, value) const log_level name = value;
+DECL_LEVELS
+#undef DECL_LEVEL
+
+//#define fprintf(...)
+
+namespace aos {
+namespace logging {
+namespace {
+
+MSG_Q_ID queue;
+uint8_t sequence = 0;
+
+// This gets run in a low-priority task to take the logs from the queue and send
+// them to the atom over a TCP socket.
+void DoTask() {
+ SendSocket sock;
+ log_crio_message msg;
+ while (true) {
+ const int ret = msgQReceive(queue, reinterpret_cast<char *>(&msg),
+ sizeof(msg), WAIT_FOREVER);
+ if (ret == ERROR) {
+ fprintf(stderr, "logging: warning: receiving a message failed"
+ " with %d (%s)", errno, strerror(errno));
+ continue;
+ }
+ if (ret != sizeof(msg)) {
+ fprintf(stderr, "logging: warning: received a message of size %d "
+ "instead of %zd\n", ret, sizeof(msg));
+ continue;
+ }
+
+ if (sock.LastStatus() != 0) {
+ if (sock.Connect(NetworkPort::kLogs,
+ configuration::GetIPAddress(
+ configuration::NetworkDevice::kAtom),
+ SOCK_STREAM) != 0) {
+ fprintf(stderr, "logging: warning: connecting failed"
+ " because of %d: %s\n", errno, strerror(errno));
+ }
+ }
+ sock.Send(&msg, sizeof(msg));
+ if (sock.LastStatus() != 0) {
+ fprintf(stderr, "logging: warning: sending '%s' failed"
+ " because of %d: %s\n", msg.message, errno, strerror(errno));
+ }
+ }
+}
+
+} // namespace
+
+void Start() {
+ queue = msgQCreate(100, // max messages
+ sizeof(log_crio_message),
+ MSG_Q_PRIORITY);
+ Task *task = new Task("LogSender",
+ (FUNCPTR)(DoTask),
+ 150); // priority
+ task->Start();
+}
+
+int Do(log_level level, const char *format, ...) {
+ log_crio_message msg;
+ msg.time = Timer::GetFPGATimestamp();
+ msg.level = level;
+ msg.sequence = __sync_fetch_and_add(&sequence, 1);
+
+ const char *continued = "...";
+ const size_t size = sizeof(msg.message) - strlen(continued);
+ va_list ap;
+ va_start(ap, format);
+ const int ret = vsnprintf(msg.message, size, format, ap);
+ va_end(ap);
+
+ if (ret < 0) {
+ fprintf(stderr, "logging: error: vsnprintf failed with %d (%s)\n",
+ errno, strerror(errno));
+ return -1;
+ } else if (static_cast<uintmax_t>(ret) >= static_cast<uintmax_t>(size)) {
+ // overwrite the NULL at the end of the existing one and
+ // copy in the one on the end of continued
+ memcpy(&msg.message[size - 1], continued, strlen(continued) + 1);
+ }
+ if (msgQSend(queue, reinterpret_cast<char *>(&msg), sizeof(msg),
+ NO_WAIT, MSG_PRI_NORMAL) == ERROR) {
+ fprintf(stderr, "logging: warning: sending message '%s'"
+ " failed with %d (%s)", msg.message, errno, strerror(errno));
+ return -1;
+ }
+
+ if (level == FATAL) {
+ aos::Die("%s", msg.message);
+ }
+
+ return 0;
+}
+
+} // namespace logging
+} // namespace aos
diff --git a/aos/crio/logging/crio_logging.h b/aos/crio/logging/crio_logging.h
new file mode 100644
index 0000000..c3dbf2a
--- /dev/null
+++ b/aos/crio/logging/crio_logging.h
@@ -0,0 +1,36 @@
+#ifndef AOS_CRIO_CRIO_LOGGING_LOGGING_H_
+#define AOS_CRIO_CRIO_LOGGING_LOGGING_H_
+
+#ifndef AOS_COMMON_LOGGING_LOGGING_H_
+#error This file may only be #included through common/logging/logging.h!!!
+#endif
+
+#undef extern
+#undef const
+#undef ERROR
+
+#include <msgQLib.h>
+#include <stdint.h>
+
+//#define LOG(level, fmt, args...) printf(STRINGIFY(level) ": " fmt, ##args)
+#define LOG(level, fmt, args...) \
+ ::aos::logging::Do(level, \
+ LOG_SOURCENAME ": " STRINGIFY(__LINE__) ": " fmt, \
+ ##args)
+//#define LOG(...)
+
+namespace aos {
+namespace logging {
+
+// Initialize internal variables and start up the task that sends the logs to
+// the atom. Must be called before Do.
+void Start();
+// The function that the LOG macro actually calls. Queues up a message for the
+// task to send. Start must be called before this function is.
+int Do(log_level level, const char *format, ...)
+ __attribute__((format(printf, 2, 3)));
+
+} // namespace logging
+} // namespace aos
+
+#endif // AOS_CRIO_CRIO_LOGGING_LOGGING_H_
diff --git a/aos/crio/messages/DriverStationDisplay.h b/aos/crio/messages/DriverStationDisplay.h
new file mode 100644
index 0000000..59d97b5
--- /dev/null
+++ b/aos/crio/messages/DriverStationDisplay.h
@@ -0,0 +1,51 @@
+#ifndef AOS_CRIO_DRIVER_STATION_DISPLAY_H_
+#define AOS_CRIO_DRIVER_STATION_DISPLAY_H_
+
+#include <stdarg.h>
+
+#include "WPILib/DriverStationLCD.h"
+
+namespace aos {
+
+class DriverStationDisplay {
+ public:
+ static void Send(int line, const char *fmt, ...)
+ __attribute__((format(printf, 2, 3))) {
+ DriverStationLCD::Line ds_line;
+ switch (line) {
+ case 0:
+ ds_line = DriverStationLCD::kMain_Line6;
+ break;
+ case 1:
+ ds_line = DriverStationLCD::kUser_Line1;
+ break;
+ case 2:
+ ds_line = DriverStationLCD::kUser_Line2;
+ break;
+ case 3:
+ ds_line = DriverStationLCD::kUser_Line3;
+ break;
+ case 4:
+ ds_line = DriverStationLCD::kUser_Line4;
+ break;
+ case 5:
+ ds_line = DriverStationLCD::kUser_Line5;
+ break;
+ case 6:
+ ds_line = DriverStationLCD::kUser_Line6;
+ break;
+ default:
+ printf("illegal line number %hhd\n", line);
+ return;
+ }
+ va_list args;
+ va_start(args, fmt);
+ DriverStationLCD::GetInstance()->VPrintfLine(ds_line, fmt, args);
+ va_end(args);
+ DriverStationLCD::GetInstance()->UpdateLCD();
+ }
+};
+
+} // namespace aos
+
+#endif
diff --git a/aos/crio/motor_server/CRIOControlLoopRunner.cpp b/aos/crio/motor_server/CRIOControlLoopRunner.cpp
new file mode 100644
index 0000000..9d6cd52
--- /dev/null
+++ b/aos/crio/motor_server/CRIOControlLoopRunner.cpp
@@ -0,0 +1,49 @@
+#include "CRIOControlLoopRunner.h"
+
+#include "aos/aos_core.h"
+#include "aos/crio/shared_libs/interrupt_bridge.h"
+#include "aos/crio/motor_server/MotorOutput.h"
+
+using ::aos::control_loops::SerializableControlLoop;
+
+namespace aos {
+namespace crio {
+
+bool CRIOControlLoopRunner::started_ = false;
+std::vector<SerializableControlLoop *> CRIOControlLoopRunner::loops_;
+Mutex CRIOControlLoopRunner::loops_lock;
+
+void CRIOControlLoopRunner::Start() {
+ if (started_) {
+ LOG(WARNING, "not going to Start twice!!\n");
+ return;
+ }
+ started_ = true;
+
+ // TODO(aschuh): Hold on to a handle to this...
+ (new WDInterruptNotifier<void>(Notify))->StartPeriodic(0.01);
+}
+
+void CRIOControlLoopRunner::AddControlLoop(SerializableControlLoop *loop) {
+ MutexLocker control_loop_goals_locker(&loops_lock);
+ loops_.push_back(loop);
+ MotorServer::RegisterControlLoopGoal(loop);
+}
+
+void CRIOControlLoopRunner::Notify(void *) {
+ // TODO(aschuh): Too many singletons/static classes!
+ SensorOutputs::UpdateAll();
+ // sensors get read first so it doesn't really matter if this takes a little bit
+ {
+ MutexLocker control_loop_goals_locker(
+ &MotorServer::control_loop_goals_lock);
+ for (auto it = loops_.begin(); it != loops_.end(); ++it) {
+ (*it)->Iterate();
+ }
+ }
+ MotorOutput::RunIterationAll();
+ MotorServer::WriteOutputs();
+}
+
+} // namespace crio
+} // namespace aos
diff --git a/aos/crio/motor_server/CRIOControlLoopRunner.h b/aos/crio/motor_server/CRIOControlLoopRunner.h
new file mode 100644
index 0000000..efed120
--- /dev/null
+++ b/aos/crio/motor_server/CRIOControlLoopRunner.h
@@ -0,0 +1,40 @@
+#ifndef AOS_CRIO_MOTOR_SERVER_CRIO_CONTROL_LOOP_RUNNER_H_
+#define AOS_CRIO_MOTOR_SERVER_CRIO_CONTROL_LOOP_RUNNER_H_
+
+#include <vector>
+#include <semLib.h>
+
+#include "aos/common/control_loop/ControlLoop.h"
+#include "aos/common/mutex.h"
+
+namespace aos {
+namespace crio {
+
+// Runs crio-side control loops. Completely static because there is no reason
+// for multiple ones and it gets rid of the problem of passing an instance
+// around.
+class CRIOControlLoopRunner {
+ public:
+ // Spawns a new Task that loops forever.
+ // No other functions should be called before this one returns.
+ static void Start();
+
+ // Adds a control loop to run.
+ // This class takes control of the instance.
+ static void AddControlLoop(control_loops::SerializableControlLoop *loop);
+
+ private:
+ static bool started_;
+
+ static std::vector<control_loops::SerializableControlLoop *> loops_;
+ static Mutex loops_lock;
+
+ // Gets called by a WDInterruptNotifier on 0.01 second intervals.
+ static void Notify(void *);
+};
+
+
+} // namespace crio
+} // namespace aos
+
+#endif
diff --git a/aos/crio/motor_server/ControlLoopGoals.h b/aos/crio/motor_server/ControlLoopGoals.h
new file mode 100644
index 0000000..f22c0a2
--- /dev/null
+++ b/aos/crio/motor_server/ControlLoopGoals.h
@@ -0,0 +1,44 @@
+#ifndef AOS_CRIO_MOTOR_SERVER_CONTROL_LOOP_GOAL_H_
+#define AOS_CRIO_MOTOR_SERVER_CONTROL_LOOP_GOAL_H_
+
+#include <vector>
+#include <semLib.h>
+
+namespace aos {
+
+// This class is used to keep track of all the control loop goals. It exists
+// because of several bugs discovered in the std::map implementation.
+class ControlLoopGoals {
+ public:
+ struct Goal {
+ const char *const name;
+ const size_t length;
+ void (*const zero)();
+ void (*const ntoh)(const char *);
+ Goal(const char *name, size_t length, void (*zero)(), void (*ntoh)(const char *)) :
+ name(name), length(length), zero(zero), ntoh(ntoh) {}
+ };
+
+ private:
+ std::vector<Goal *> goals_;
+
+ public:
+ ControlLoopGoals() {}
+ void Add(const char *name, size_t length, void (*zero)(), void (*ntoh)(const char *)) {
+ char *storage = new char[10];
+ memcpy(storage, name, sizeof(storage));
+ goals_.push_back(new Goal(storage, length, zero, ntoh));
+ }
+ const Goal *Get(const char *name) {
+ for (auto it = goals_.begin(); it != goals_.end(); ++it) {
+ if (memcmp((*it)->name, name, sizeof((*it)->name)) == 0) {
+ return *it;
+ }
+ }
+ return NULL;
+ }
+};
+
+} // namespace aos
+
+#endif
diff --git a/aos/crio/motor_server/MotorControllerOutput.cpp b/aos/crio/motor_server/MotorControllerOutput.cpp
new file mode 100644
index 0000000..a0897b4
--- /dev/null
+++ b/aos/crio/motor_server/MotorControllerOutput.cpp
@@ -0,0 +1,103 @@
+#include "aos/crio/motor_server/MotorControllerOutput.h"
+
+#include "aos/aos_core.h"
+#include "aos/common/byteorder.h"
+#include "aos/common/commonmath.h"
+
+namespace aos {
+
+void LinearizedVictor::Set(float speed, UINT8 syncGroup) {
+ speed_ = speed;
+ Victor::Set(Linearize(speed), syncGroup);
+}
+
+float LinearizedVictor::Get() {
+ return speed_;
+}
+
+void LinearizedVictor::Disable() {
+ Victor::Disable();
+ speed_ = 0.0;
+}
+
+double LinearizedVictor::Linearize(double goal_speed) {
+ // These values were derived by putting the robot up on blocks, and driving it
+ // at various speeds. The power required to drive at these speeds was then
+ // recorded and fit with gnuplot.
+ const double deadband_value = 0.082;
+ // If we are outside the range such that the motor is actually moving,
+ // subtract off the constant offset from the deadband. This makes the
+ // function odd and intersect the origin, making the fitting easier to do.
+ if (goal_speed > deadband_value) {
+ goal_speed -= deadband_value;
+ } else if (goal_speed < -deadband_value) {
+ goal_speed += deadband_value;
+ } else {
+ goal_speed = 0.0;
+ }
+ goal_speed = goal_speed / (1.0 - deadband_value);
+
+ double goal_speed2 = goal_speed * goal_speed;
+ double goal_speed3 = goal_speed2 * goal_speed;
+ double goal_speed4 = goal_speed3 * goal_speed;
+ double goal_speed5 = goal_speed4 * goal_speed;
+ double goal_speed6 = goal_speed5 * goal_speed;
+ double goal_speed7 = goal_speed6 * goal_speed;
+
+ // Constants for the 5th order polynomial
+ double victor_fit_e1 = 0.437239;
+ double victor_fit_c1 = -1.56847;
+ double victor_fit_a1 = (- (125.0 * victor_fit_e1 + 125.0
+ * victor_fit_c1 - 116.0) / 125.0);
+ double answer_5th_order = (victor_fit_a1 * goal_speed5
+ + victor_fit_c1 * goal_speed3
+ + victor_fit_e1 * goal_speed);
+
+ // Constants for the 7th order polynomial
+ double victor_fit_c2 = -5.46889;
+ double victor_fit_e2 = 2.24214;
+ double victor_fit_g2 = -0.042375;
+ double victor_fit_a2 = (- (125.0 * (victor_fit_c2 + victor_fit_e2
+ + victor_fit_g2) - 116.0) / 125.0);
+ double answer_7th_order = (victor_fit_a2 * goal_speed7
+ + victor_fit_c2 * goal_speed5
+ + victor_fit_e2 * goal_speed3
+ + victor_fit_g2 * goal_speed);
+
+
+ // Average the 5th and 7th order polynomials, and add a bit of linear power in
+ // as well. The average turns out to nicely fit the data in gnuplot with nice
+ // smooth curves, and the linear power gives it a bit more punch at low speeds
+ // again. Stupid victors.
+ double answer = 0.85 * 0.5 * (answer_7th_order + answer_5th_order)
+ + .15 * goal_speed * (1.0 - deadband_value);
+
+ // Add the deadband power back in to make it so that the motor starts moving
+ // when any power is applied. This is what the fitting assumes.
+ if (answer > 0.001) {
+ answer += deadband_value;
+ } else if (answer < -0.001) {
+ answer -= deadband_value;
+ }
+
+ return Clip(answer, -1.0, 1.0);
+}
+
+bool MotorControllerOutput::ReadValue(ByteBuffer &buff) {
+ const float val = buff.read_float();
+ if (val == (1.0 / 0.0)) {
+ return false;
+ }
+ value = val;
+ return true;
+}
+void MotorControllerOutput::SetValue() {
+ output.Set(value);
+}
+void MotorControllerOutput::NoValue() {
+ // this is NOT a Set(0.0); it's the same as when the robot is disabled
+ output.Disable();
+}
+
+} // namespace aos
+
diff --git a/aos/crio/motor_server/MotorControllerOutput.h b/aos/crio/motor_server/MotorControllerOutput.h
new file mode 100644
index 0000000..41c3546
--- /dev/null
+++ b/aos/crio/motor_server/MotorControllerOutput.h
@@ -0,0 +1,68 @@
+#ifndef AOS_CRIO_MOTOR_SERVER_MOTOR_CONTROLLER_OUTPUT_H_
+#define AOS_CRIO_MOTOR_SERVER_MOTOR_CONTROLLER_OUTPUT_H_
+
+#include "aos/crio/motor_server/OutputDevice.h"
+
+#include "aos/crio/Talon.h"
+
+#include "WPILib/SpeedController.h"
+#include "WPILib/Jaguar.h"
+#include "WPILib/CANJaguar.h"
+#include "WPILib/Victor.h"
+
+namespace aos {
+
+// LinearizedVictor is a Victor that transforms the set values to linearize the
+// hardware's response curve.
+class LinearizedVictor : public Victor {
+ public:
+ explicit LinearizedVictor(uint32_t channel) : Victor(channel), speed_(0) {}
+ virtual void Set(float speed, UINT8 syncGroup=0);
+ virtual float Get();
+ virtual void Disable();
+
+ // Returns the linearized motor power to apply to get the motor to go at the
+ // provided goal_speed.
+ static double Linearize(double goal_speed);
+
+ private:
+ // The speed last sent to the Victor.
+ float speed_;
+};
+
+class MotorControllerOutput : public OutputDevice {
+ private:
+ SpeedController &output;
+ protected:
+ double value;
+ MotorControllerOutput(SpeedController *output) : OutputDevice(), output(*output) {
+ value = 0.0;
+ }
+ // TODO(brians) add virtual destructor?
+
+ virtual bool ReadValue(ByteBuffer &buff);
+ virtual void SetValue();
+ virtual void NoValue();
+};
+
+class JaguarOutput : public MotorControllerOutput {
+ public:
+ JaguarOutput(uint32_t port) : MotorControllerOutput(new Jaguar(port)) {}
+};
+class CANJaguarOutput : public MotorControllerOutput {
+ public:
+ CANJaguarOutput(uint32_t port) : MotorControllerOutput(new CANJaguar(port)) {}
+};
+class VictorOutput : public MotorControllerOutput {
+ public:
+ VictorOutput(uint32_t port)
+ : MotorControllerOutput(new LinearizedVictor(port)) {}
+};
+class TalonOutput : public MotorControllerOutput {
+ public:
+ TalonOutput(uint32_t port) : MotorControllerOutput(new Talon(port)) {}
+};
+
+} // namespace aos
+
+#endif
diff --git a/aos/crio/motor_server/MotorOutput.cpp b/aos/crio/motor_server/MotorOutput.cpp
new file mode 100644
index 0000000..f2e9925
--- /dev/null
+++ b/aos/crio/motor_server/MotorOutput.cpp
@@ -0,0 +1,22 @@
+#include "MotorOutput.h"
+
+namespace aos {
+
+SEM_ID MotorOutput::lock = semBCreate(SEM_Q_PRIORITY, SEM_FULL);
+std::vector<MotorOutput *> MotorOutput::instances;
+
+void MotorOutput::Run() {
+ semTake(lock, WAIT_FOREVER);
+ instances.push_back(this);
+ semGive(lock);
+}
+void MotorOutput::RunIterationAll() {
+ semTake(lock, WAIT_FOREVER);
+ for (auto it = instances.begin(); it != instances.end(); ++it) {
+ (*it)->RunIteration();
+ }
+ semGive(lock);
+}
+
+} // namespace aos
+
diff --git a/aos/crio/motor_server/MotorOutput.h b/aos/crio/motor_server/MotorOutput.h
new file mode 100644
index 0000000..af7c803
--- /dev/null
+++ b/aos/crio/motor_server/MotorOutput.h
@@ -0,0 +1,27 @@
+#ifndef AOS_CRIO_MOTOR_SERVER_MOTOR_OUTPUT_H_
+#define AOS_CRIO_MOTOR_SERVER_MOTOR_OUTPUT_H_
+
+#include <vector>
+#include <semLib.h>
+
+namespace aos {
+
+// The place where the outputs from crio control loops get written out to the
+// motors.
+class MotorOutput {
+ public:
+ // Call RunIteration on all instances that have been Run.
+ static void RunIterationAll();
+ void Run();
+ protected:
+ // Write the outputs from crio control loops to wherever they go.
+ virtual void RunIteration() = 0;
+ private:
+ static std::vector<MotorOutput *> instances;
+ static SEM_ID lock;
+};
+
+} // namespace aos
+
+#endif
+
diff --git a/aos/crio/motor_server/MotorServer.cpp b/aos/crio/motor_server/MotorServer.cpp
new file mode 100644
index 0000000..77a0579
--- /dev/null
+++ b/aos/crio/motor_server/MotorServer.cpp
@@ -0,0 +1,227 @@
+#include "aos/crio/motor_server/MotorServer.h"
+
+#include <stdio.h>
+#include <stdlib.h>
+#include "usrLib.h"
+#include "aos/common/inttypes.h"
+
+#include "WPILib/Timer.h"
+#include "WPILib/Task.h"
+
+#include "aos/aos_core.h"
+#include "aos/crio/motor_server/MotorControllerOutput.h"
+#include "aos/crio/motor_server/SolenoidOutput.h"
+#include "aos/common/Configuration.h"
+
+namespace aos {
+namespace crio {
+
+ByteBuffer MotorServer::buff(4096);
+DriverStationLCD *MotorServer::ds_lcd(NULL);
+int MotorServer::count(0);
+ReceiveSocket *MotorServer::sock(NULL);
+SEM_ID MotorServer::motorSync = semBCreate(SEM_Q_PRIORITY, SEM_FULL);
+OutputDevice *MotorServer::output_devices[256][kMaxOutputDeviceNumber];
+Mutex MotorServer::control_loop_goals_lock;
+::std::map<uint32_t,
+ control_loops::SerializableControlLoop *> MotorServer::loops;
+Task *MotorServer::tcpTask;
+void MotorServer::Start() {
+ sock = new ReceiveSocket(NetworkPort::kMotors);
+
+ memset(output_devices, 0x00, sizeof(output_devices));
+
+ tcpTask = new Task("MRLoop",
+ reinterpret_cast<FUNCPTR>(RunReaderTask),
+ WORK_PRIORITY);
+
+ tcpTask->Start();
+}
+
+void MotorServer::ProcessBuf() {
+ semTake(motorSync, WAIT_FOREVER);
+ bool cont = true;
+ while (true) {
+ if (!cont) {
+ LOG(WARNING, "Malformed Packet\n");
+ goto end;
+ }
+ switch (const int value = buff.read_char()) {
+ case 'g':
+ cont = ProcessControlLoopGoal();
+ break;
+ case 'd':
+ cont = ProcessDSLine();
+ break;
+ case -1:
+ goto end;
+ default:
+ cont = ProcessOutputDevice(value);
+ break;
+ }
+ }
+end:
+ ++count;
+ semGive(motorSync);
+}
+bool MotorServer::ProcessOutputDevice(const int type) {
+ const int id = buff.read_char(); // 1-indexed
+ if (id < 1 || id > static_cast<ssize_t>(kMaxOutputDeviceNumber)) {
+ if (id != -1) {
+ LOG(ERROR, "illegal OutputDevice id %d\n", id);
+ }
+ return false;
+ }
+
+ if (output_devices[type][id - 1] == NULL) {
+ switch (type) {
+ case 'v':
+ output_devices[type][id - 1] = new VictorOutput(id);
+ break;
+ case 'j':
+ output_devices[type][id - 1] = new JaguarOutput(id);
+ break;
+ case 'c':
+ output_devices[type][id - 1] = new CANJaguarOutput(id);
+ break;
+ case 't':
+ output_devices[type][id - 1] = new TalonOutput(id);
+ break;
+ case 's':
+ output_devices[type][id - 1] = new SolenoidOutput(id);
+ break;
+ default:
+ LOG(ERROR, "unrecognized OutputDevice type %d\n", type);
+ return false;
+ }
+ }
+ return output_devices[type][id - 1]->ReadValue(buff);
+}
+
+bool MotorServer::ProcessDSLine() {
+ int line = buff.read_char();
+ if (line == -1) {
+ return false;
+ }
+ // TODO(brians): Subfunction
+ DriverStationLCD::Line ds_line;
+ switch (line) {
+ case 0:
+ ds_line = DriverStationLCD::kMain_Line6;
+ break;
+ case 1:
+ ds_line = DriverStationLCD::kUser_Line1;
+ break;
+ case 2:
+ ds_line = DriverStationLCD::kUser_Line2;
+ break;
+ case 3:
+ ds_line = DriverStationLCD::kUser_Line3;
+ break;
+ case 4:
+ ds_line = DriverStationLCD::kUser_Line4;
+ break;
+ case 5:
+ ds_line = DriverStationLCD::kUser_Line5;
+ break;
+ case 6:
+ ds_line = DriverStationLCD::kUser_Line6;
+ break;
+ default:
+ LOG(ERROR, "illegal line number %hhd\n", line);
+ return false;
+ }
+ // TODO(brians) see if this mess with not creating the DriverStationLCD for a
+ // bit is actually needed
+ static int ds_lcd_counts = 0; // to prevent crashes at startup
+ if (ds_lcd == NULL) {
+ if (ds_lcd_counts < 100) {
+ ++ds_lcd_counts;
+ } else {
+ ++ds_lcd_counts;
+ ds_lcd = DriverStationLCD::GetInstance();
+ }
+ }
+ char buf[DriverStationLCD::kLineLength];
+ buff.read_string(buf, sizeof(buf));
+ buf[sizeof(buf) - 1] = 0;
+ if (ds_lcd != NULL) {
+ ds_lcd->PrintfLine(ds_line, "%s", buf);
+ }
+ return true;
+}
+
+void MotorServer::RegisterControlLoopGoal(
+ control_loops::SerializableControlLoop *control_loop) {
+ uint32_t unique_id = control_loop->UniqueID();
+
+ bool replaced;
+ {
+ MutexLocker control_loop_goals_locker(&control_loop_goals_lock);
+ replaced = !InsertIntoMap(&loops, unique_id, control_loop);
+ }
+ if (replaced) {
+ LOG(ERROR, "Replaced a key for unique id 0x%"PRIx32"\n", unique_id);
+ }
+}
+
+bool MotorServer::ProcessControlLoopGoal() {
+ // Read back a uint32_t with the hash.
+ uint32_t hash;
+ if (!buff.read_uint32(&hash)) return false;
+ MutexLocker control_loop_goals_locker(&control_loop_goals_lock);
+
+ control_loops::SerializableControlLoop *loop;
+ if (!GetFromMap(loops, hash, &loop)) {
+ return false;
+ }
+ const size_t length = loop->SeralizedSize();
+ char *const goal_bytes = buff.get_bytes(length);
+ if (goal_bytes == NULL) {
+ return false;
+ } else {
+ loop->Deserialize(goal_bytes);
+ }
+ return true;
+}
+
+void MotorServer::RunReaderTask() {
+ while (true) {
+ if (buff.recv_from_sock(sock)) {
+ ProcessBuf();
+ }
+ }
+}
+void MotorServer::WriteOutputs() {
+ static int last_count = 0, bad_counts = 0;
+ semTake(motorSync, WAIT_FOREVER);
+ if (last_count != count) {
+ bad_counts = 0;
+ } else {
+ ++bad_counts;
+ }
+ last_count = count;
+ // both loops iterate over all elements of output_devices by indexing off the
+ // end of output_devices[0]
+ if (bad_counts > 2) {
+ LOG(WARNING, "no new values. stopping all outputs\n");
+ for (size_t i = 0; i < sizeof(output_devices) / sizeof(output_devices[0][0]); ++i) {
+ if (output_devices[0][i] != NULL) {
+ output_devices[0][i]->NoValue();
+ }
+ }
+ } else {
+ for (size_t i = 0; i < sizeof(output_devices) / sizeof(output_devices[0][0]); ++i) {
+ if (output_devices[0][i] != NULL) {
+ output_devices[0][i]->SetValue();
+ }
+ }
+ }
+ if (ds_lcd != NULL) {
+ ds_lcd->UpdateLCD();
+ }
+ semGive(motorSync);
+}
+
+} // namespace crio
+} // namespace aos
diff --git a/aos/crio/motor_server/MotorServer.h b/aos/crio/motor_server/MotorServer.h
new file mode 100644
index 0000000..0126663
--- /dev/null
+++ b/aos/crio/motor_server/MotorServer.h
@@ -0,0 +1,87 @@
+#ifndef AOS_CRIO_MOTOR_SERVER_MOTOR_SERVER_H_
+#define AOS_CRIO_MOTOR_SERVER_MOTOR_SERVER_H_
+
+#include <vxWorks.h>
+#include <timers.h>
+#include <string.h>
+#include "WPILib/Task.h"
+#include "WPILib/Victor.h"
+#include "WPILib/Jaguar.h"
+#include "WPILib/Solenoid.h"
+#include "sockLib.h"
+#include <inetLib.h>
+#include <stdio.h>
+#include <selectLib.h>
+#include <stdlib.h>
+#include <time.h>
+#include <map>
+#include <string>
+
+#include "WPILib/DriverStationLCD.h"
+
+#include "aos/common/control_loop/ControlLoop.h"
+#include "aos/common/inttypes.h"
+#include "aos/common/messages/QueueHolder.h"
+#include "aos/common/mutex.h"
+#include "aos/common/network/ReceiveSocket.h"
+#include "aos/common/network/SendSocket.h"
+#include "aos/crio/motor_server/ControlLoopGoals.h"
+#include "aos/crio/motor_server/OutputDevice.h"
+#include "aos/crio/motor_server/SensorSender.h"
+#include "aos/crio/shared_libs/ByteBuffer.h"
+#include "aos/map_utils.h"
+
+namespace aos {
+namespace crio {
+
+class CRIOControlLoopRunner;
+class MotorServer {
+ public:
+ static void Start();
+
+ // Adds the given control loop's goal queue to the list of ones to process.
+ static void RegisterControlLoopGoal(
+ control_loops::SerializableControlLoop *control_loop);
+
+ static const int32_t WORK_PRIORITY = 100;
+
+ private:
+ friend class CRIOControlLoopRunner;
+ // Counter for how many times new values come in. Used to stop all the
+ // outputs if values stop.
+ // Would take days to overflow.
+ static int count;
+ static SEM_ID motorSync;
+ // Gets called by CRIOControlLoopRunner every 10ms after it runs all of the
+ // control loops.
+ static void WriteOutputs();
+
+ static void RunReaderTask();
+ static Task *tcpTask;
+ static ReceiveSocket *sock;
+ static ByteBuffer buff;
+
+ static DriverStationLCD *ds_lcd;
+ static bool ProcessDSLine();
+
+ static const size_t kMaxOutputDeviceNumber = 10;
+ static OutputDevice *output_devices[256][kMaxOutputDeviceNumber];
+ static bool ProcessOutputDevice(const int type);
+
+ // Go through the whole buffer and call the appropriate Process* methods to
+ // process each part.
+ static void ProcessBuf();
+
+ static bool ProcessControlLoopGoal();
+ // Locked whenever adding/using the control loop goals maps.
+ // Also used by CRIOControlLoopRunner while modifying any of the data
+ // structures. Used by both of them while reading/writing from
+ // the goal queues.
+ static Mutex control_loop_goals_lock;
+ static ::std::map<uint32_t, control_loops::SerializableControlLoop *> loops;
+};
+
+} // namespace crio
+} // namespace aos
+
+#endif
diff --git a/aos/crio/motor_server/OutputDevice.h b/aos/crio/motor_server/OutputDevice.h
new file mode 100644
index 0000000..0789a68
--- /dev/null
+++ b/aos/crio/motor_server/OutputDevice.h
@@ -0,0 +1,26 @@
+#ifndef __CRIO_MOTOR_SERVER_OUTPUT_DEVICE_H_
+#define __CRIO_MOTOR_SERVER_OUTPUT_DEVICE_H_
+
+#include <stdint.h>
+#include "aos/crio/shared_libs/ByteBuffer.h"
+
+namespace aos {
+
+class OutputDevice {
+ protected:
+ OutputDevice() {
+ }
+ public:
+ // Reads the value out of buff and stores it somewhere for SetValue to use.
+ // Returns whether or not it successfully read a whole value out of buff.
+ virtual bool ReadValue(ByteBuffer &buff) = 0;
+ // Actually sets the output device to the value saved by ReadValue.
+ virtual void SetValue() = 0;
+ // Gets called when no values come in for a while.
+ virtual void NoValue() = 0;
+};
+
+} // namespace aos
+
+#endif
+
diff --git a/aos/crio/motor_server/SensorOutput-tmpl.h b/aos/crio/motor_server/SensorOutput-tmpl.h
new file mode 100644
index 0000000..d6b8b69
--- /dev/null
+++ b/aos/crio/motor_server/SensorOutput-tmpl.h
@@ -0,0 +1,27 @@
+#include "aos/common/input/SensorInput.h"
+
+namespace aos {
+
+template<class Values> std::vector<SensorOutput<Values> *> SensorOutput<Values>::output_running_;
+template<class Values> void SensorOutput<Values>::Run() {
+ semTake(lock_, WAIT_FOREVER);
+ output_running_.push_back(this);
+ outputs_running_.push_back(this);
+ semGive(lock_);
+}
+
+template<class Values> void SensorOutput<Values>::RunIterationAll(Values &vals) {
+ semTake(lock_, WAIT_FOREVER);
+ for (auto it = output_running_.begin(); it != output_running_.end(); ++it) {
+ (*it)->RunIteration(vals);
+ }
+ semGive(lock_);
+}
+template<class Values> void SensorOutput<Values>::Update() {
+ Values vals;
+ RunIteration(vals);
+ SensorInput<Values>::RunIterationAll(vals);
+}
+
+} // namespace aos
+
diff --git a/aos/crio/motor_server/SensorOutput.cpp b/aos/crio/motor_server/SensorOutput.cpp
new file mode 100644
index 0000000..b887885
--- /dev/null
+++ b/aos/crio/motor_server/SensorOutput.cpp
@@ -0,0 +1,17 @@
+#include "aos/crio/motor_server/SensorOutput.h"
+
+namespace aos {
+
+SEM_ID SensorOutputs::lock_ = semBCreate(SEM_Q_PRIORITY, SEM_FULL);
+std::vector<SensorOutputs *> SensorOutputs::outputs_running_;
+
+void SensorOutputs::UpdateAll() {
+ semTake(lock_, WAIT_FOREVER);
+ for (auto it = outputs_running_.begin(); it != outputs_running_.end(); ++it) {
+ (*it)->Update();
+ }
+ semGive(lock_);
+}
+
+} // namespace aos
+
diff --git a/aos/crio/motor_server/SensorOutput.h b/aos/crio/motor_server/SensorOutput.h
new file mode 100644
index 0000000..9e30cb9
--- /dev/null
+++ b/aos/crio/motor_server/SensorOutput.h
@@ -0,0 +1,48 @@
+#ifndef AOS_CRIO_MOTOR_SERVER_SENSOR_OUTPUT_H_
+#define AOS_CRIO_MOTOR_SERVER_SENSOR_OUTPUT_H_
+
+#include <semLib.h>
+#include <vector>
+
+namespace aos {
+
+// Keeps track of instances of all instantiations.
+class SensorOutputs {
+ public:
+ // Calls RunIteration on all instances and then runs all SensorInput
+ // subclasses for that type.
+ static void UpdateAll();
+ private:
+ static SEM_ID lock_;
+ static std::vector<SensorOutputs *> outputs_running_;
+ protected:
+ // Calls RunIteration with a temporary Values instance and then runs all
+ // SensorInput subclasses with the same Values type.
+ virtual void Update() = 0;
+};
+
+// Class for implementing crio code that reads sensor values and puts them into
+// the sensor struct.
+template<class Values> class SensorOutput : public SensorOutputs {
+ protected:
+ // Fills out vals with the current data.
+ // May not be called at anything close to consistent intervals and may be
+ // called simultaneously with different arguments, so it must be reentrant.
+ virtual void RunIteration(Values &vals) = 0;
+ public:
+ // Sets it up so that RunIteration will get called when appropriate.
+ void Run();
+
+ // Calls RunIteration on all instances with vals.
+ static void RunIterationAll(Values &vals);
+ private:
+ static std::vector<SensorOutput<Values> *> output_running_;
+ virtual void Update();
+};
+
+} // namespace aos
+
+#include "SensorOutput-tmpl.h"
+
+#endif
+
diff --git a/aos/crio/motor_server/SensorSender-tmpl.h b/aos/crio/motor_server/SensorSender-tmpl.h
new file mode 100644
index 0000000..93fe73d
--- /dev/null
+++ b/aos/crio/motor_server/SensorSender-tmpl.h
@@ -0,0 +1,21 @@
+#include "WPILib/Task.h"
+#include "WPILib/Timer.h"
+#include "aos/crio/motor_server/SensorOutput.h"
+#include "aos/common/network/SendSocket.h"
+#include "aos/common/Configuration.h"
+
+namespace aos {
+
+template<class Values> void SensorSender<Values>::Run() {
+ SendSocket sock(NetworkPort::kSensors,
+ configuration::GetIPAddress(configuration::NetworkDevice::kAtom));
+ Values vals;
+ while (true) {
+ Wait(0.0015);
+ SensorOutput<Values>::RunIterationAll(vals);
+ sock.Send(&vals, sizeof(vals));
+ }
+}
+
+} // namespace aos
+
diff --git a/aos/crio/motor_server/SensorSender.h b/aos/crio/motor_server/SensorSender.h
new file mode 100644
index 0000000..135e1fa
--- /dev/null
+++ b/aos/crio/motor_server/SensorSender.h
@@ -0,0 +1,23 @@
+#ifndef __CRIO_SENSOR_SENDER_H_
+#define __CRIO_SENSOR_SENDER_H_
+
+namespace aos {
+
+// A class that handles sending all of the sensor values to the atom.
+// Designed for an instantiation (aos::SensorSender<X>) to be AOS_RUN_FORKed,
+// NOT a subclass.
+// Values is the type of the struct that will get sent out over the network.
+// Note: it should the same as the instance of TODO(brians) on the atom and any
+// SensorOutput instances that you want to feed into an instance of this.
+template<class Values> class SensorSender {
+ public:
+ // Loops forever.
+ void Run();
+};
+
+} // namespace aos
+
+#include "SensorSender-tmpl.h"
+
+#endif
+
diff --git a/aos/crio/motor_server/SolenoidOutput.h b/aos/crio/motor_server/SolenoidOutput.h
new file mode 100644
index 0000000..6a6c838
--- /dev/null
+++ b/aos/crio/motor_server/SolenoidOutput.h
@@ -0,0 +1,38 @@
+#ifndef __CRIO_MOTOR_SERVER_SOLENOID_OUTPUT_H_
+#define __CRIO_MOTOR_SERVER_SOLENOID_OUTPUT_H_
+
+#include "aos/crio/motor_server/OutputDevice.h"
+
+namespace aos {
+
+class SolenoidOutput : public OutputDevice {
+ private:
+ Solenoid solenoid;
+ bool value;
+ public:
+ SolenoidOutput(uint32_t port) : OutputDevice(), solenoid(port), value(false) {
+ }
+ protected:
+ virtual bool ReadValue(ByteBuffer &buff) {
+ const int on = buff.read_char();
+ if (on != 0 && on != 1) {
+ if (on != -1) {
+ LOG(ERROR, "illegal solenoid value %d\n", on);
+ }
+ return false;
+ }
+ value = on;
+ return true;
+ }
+ virtual void SetValue() {
+ solenoid.Set(value);
+ }
+ virtual void NoValue() {
+ // leave the solenoid in its previous state
+ }
+};
+
+} // namespace aos
+
+#endif
+
diff --git a/aos/crio/motor_server/victor_drive.rb b/aos/crio/motor_server/victor_drive.rb
new file mode 100644
index 0000000..7de9706
--- /dev/null
+++ b/aos/crio/motor_server/victor_drive.rb
@@ -0,0 +1,30 @@
+require "socket"
+$sock = UDPSocket.new()
+$sock.connect("10.59.71.2",9123)
+def short(val)
+ val += 1.0
+ if(val < 0)
+ val = 0
+ end
+ val = (val * 256 * 128).to_i
+ v1 = val / 256
+ v2 = val % 256
+ if(v1 > 255)
+ v1 = 255
+ v2 = 255
+ end
+ return(v1.chr + v2.chr)
+end
+def jaguar(port,val)
+ $sock.send("j#{port.chr}#{short(val)}",0)
+end
+trap(2) do
+ jaguar(4,0)
+ jaguar(3,0)
+ exit!
+end
+while true
+ jaguar(4,Math.cos(Time.now.to_f))
+ jaguar(3,Math.cos(Time.now.to_f))
+ sleep(0.01)
+end
diff --git a/aos/crio/queue-tmpl.h b/aos/crio/queue-tmpl.h
new file mode 100644
index 0000000..94bc100
--- /dev/null
+++ b/aos/crio/queue-tmpl.h
@@ -0,0 +1,57 @@
+namespace aos {
+
+// The easiest way to hack this together is to have the scoped msg pointer not
+// manage the pointer, since it is a pointer to the only msg in the queue.
+template <class T>
+bool ScopedMessagePtr<T>::Send() {
+ msg_->SetTimeToNow();
+ reset();
+ return true;
+}
+
+template <class T>
+bool ScopedMessagePtr<T>::SendBlocking() {
+ msg_->SetTimeToNow();
+ reset();
+ return true;
+}
+
+template <class T>
+void ScopedMessagePtr<T>::reset(T *msg) {
+ msg_ = msg;
+}
+
+template <class T>
+void Queue<T>::Init() {}
+
+template <class T>
+bool Queue<T>::FetchNext() {
+ Init();
+ return true;
+}
+
+template <class T>
+bool Queue<T>::FetchNextBlocking() {
+ Init();
+ return true;
+}
+
+template <class T>
+bool Queue<T>::FetchLatest() {
+ Init();
+ return true;
+}
+
+template <class T>
+ScopedMessagePtr<T> Queue<T>::MakeMessage() {
+ Init();
+ return ScopedMessagePtr<T>(&msg_);
+}
+
+template <class T>
+aos::MessageBuilder<T> Queue<T>::MakeWithBuilder() {
+ Init();
+ return aos::MessageBuilder<T>(&msg_);
+}
+
+} // namespace aos
diff --git a/aos/crio/queue_test.cc b/aos/crio/queue_test.cc
new file mode 100644
index 0000000..39609bc
--- /dev/null
+++ b/aos/crio/queue_test.cc
@@ -0,0 +1,122 @@
+#include <unistd.h>
+
+#include <memory>
+
+#include "gtest/gtest.h"
+#define __TEST_VXWORKS__
+#include "aos/common/test_queue.q.h"
+
+using ::aos::time::Time;
+
+namespace aos {
+namespace common {
+namespace testing {
+
+class CRIOQueueTest : public ::testing::Test {
+ protected:
+ // Create a new instance of the test queue that is fresh.
+ ::aos::Queue<TestingMessage> my_test_queue;
+
+ CRIOQueueTest() : my_test_queue(".aos.common.testing.test_queue") {}
+};
+
+// Tests that we can send a message with the message pointer and get it back.
+TEST_F(CRIOQueueTest, SendMessage) {
+ ScopedMessagePtr<TestingMessage> msg = my_test_queue.MakeMessage();
+ msg->test_bool = true;
+ msg->test_int = 0x971;
+ msg.Send();
+
+ my_test_queue.FetchLatest();
+ EXPECT_TRUE(my_test_queue->test_bool);
+ EXPECT_EQ(0x971, my_test_queue->test_int);
+}
+
+// Tests that we can send a message with the builder and get it back.
+TEST_F(CRIOQueueTest, SendWithBuilder) {
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
+
+ my_test_queue.FetchLatest();
+ EXPECT_EQ(true, my_test_queue->test_bool);
+ EXPECT_EQ(0x971, my_test_queue->test_int);
+ EXPECT_EQ(true, my_test_queue.IsNewerThanMS(10000));
+}
+
+// Tests that various pointer deref functions at least seem to work.
+TEST_F(CRIOQueueTest, PointerDeref) {
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
+
+ my_test_queue.FetchLatest();
+ const TestingMessage *msg_ptr = my_test_queue.get();
+ ASSERT_NE(static_cast<TestingMessage*>(NULL), msg_ptr);
+ EXPECT_EQ(0x971, msg_ptr->test_int);
+ EXPECT_EQ(msg_ptr, &(*my_test_queue));
+}
+
+// Tests that FetchLatest skips a missing message.
+TEST_F(CRIOQueueTest, FetchLatest) {
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x254).Send();
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
+
+ my_test_queue.FetchLatest();
+ EXPECT_EQ(0x971, my_test_queue->test_int);
+}
+
+// Tests that age makes some sense.
+TEST_F(CRIOQueueTest, Age) {
+ my_test_queue.MakeWithBuilder().test_bool(true).test_int(0x971).Send();
+
+ my_test_queue.FetchLatest();
+ EXPECT_TRUE(my_test_queue.IsNewerThanMS(100));
+ const Time age = my_test_queue.Age();
+ EXPECT_EQ(0, age.sec());
+ EXPECT_GE(100000000, age.nsec());
+}
+
+
+class CRIOMessageTest : public ::testing::Test {
+ public:
+ TestingMessage msg;
+};
+
+TEST_F(CRIOMessageTest, Zeroing) {
+ msg.test_bool = true;
+ msg.test_int = 0x254;
+ msg.SetTimeToNow();
+
+ msg.Zero();
+
+ EXPECT_FALSE(msg.test_bool);
+ EXPECT_EQ(0, msg.test_int);
+ EXPECT_EQ(0, msg.sent_time.sec());
+ EXPECT_EQ(0, msg.sent_time.nsec());
+}
+
+TEST_F(CRIOMessageTest, Size) {
+ EXPECT_EQ(static_cast<size_t>(13), msg.Size());
+}
+
+TEST_F(CRIOMessageTest, Serialize) {
+ char serialized_data[msg.Size()];
+ msg.test_bool = true;
+ msg.test_int = 0x254;
+ msg.SetTimeToNow();
+
+ msg.Serialize(serialized_data);
+
+ TestingMessage new_msg;
+ new_msg.Deserialize(serialized_data);
+
+ EXPECT_EQ(msg.test_bool, new_msg.test_bool);
+ EXPECT_EQ(msg.test_int, new_msg.test_int);
+ EXPECT_EQ(msg.sent_time, new_msg.sent_time);
+}
+
+TEST_F(CRIOMessageTest, SetNow) {
+ msg.SetTimeToNow();
+ EXPECT_LE(msg.sent_time - Time::Now(), Time::InMS(20));
+}
+
+} // namespace testing
+} // namespace common
+} // namespace aos
diff --git a/aos/crio/shared_libs/ByteBuffer.h b/aos/crio/shared_libs/ByteBuffer.h
new file mode 100644
index 0000000..b5c4902
--- /dev/null
+++ b/aos/crio/shared_libs/ByteBuffer.h
@@ -0,0 +1,91 @@
+#ifndef __CRIO_SHARED_LIBS_BYTE_BUFFER_H_
+#define __CRIO_SHARED_LIBS_BYTE_BUFFER_H_
+
+#include "aos/common/network/ReceiveSocket.h"
+#include <algorithm>
+
+namespace aos {
+
+class ByteBuffer {
+ public:
+ int m_size;
+ int m_length;
+ int m_i;
+ char *m_buffer;
+ bool recv_from_sock(ReceiveSocket *sock) {
+ m_length = sock->Recv(m_buffer, m_size, 40000);
+ if (m_length < 0) {
+ m_length = 0;
+ }
+ m_i = 0;
+ return m_length != 0;
+ }
+ ByteBuffer(int size) {
+ m_buffer = new char(size);
+ m_size = size;
+ }
+ ~ByteBuffer() {
+ delete m_buffer;
+ }
+ // Reads an uint32_t into *number and returns true on success. *number is
+ // unmodified on failure.
+ bool read_uint32(uint32_t *number) {
+ uint32_t vals[4];
+ if (m_i + 4 > m_length) {
+ m_i = m_length;
+ return false;
+ }
+ for (int i = 0; i < 4; ++i) {
+ vals[i] = read_char();
+ }
+ *number = vals[3] + (vals[2] << 8) + (vals[1] << 16) + (vals[0] << 24);
+ return true;
+ }
+ float read_float() {
+ if (m_i + 4 <= m_length) {
+ float r;
+ memcpy(&r, &m_buffer[m_i], 4);
+ m_i += 4;
+ return r;
+ } else {
+ return 1.0 / 0.0;
+ }
+ }
+ int read_char() {
+ if (m_i < m_length) {
+ int val = m_buffer[m_i];
+ m_i ++;
+ return val;
+ } else {
+ return -1;
+ }
+ }
+
+ int read_string(char *buf, size_t max_len) {
+ int data_len = read_char();
+ if (data_len <= 0) {
+ return -1;
+ }
+ size_t to_read = std::min<size_t>(static_cast<uint8_t>(data_len), max_len);
+ memcpy(buf, &m_buffer[m_i], to_read);
+ m_i += to_read;
+ return 0;
+ }
+ // Returns success or not.
+ bool read_bytes(void *buf, size_t bytes) {
+ if (m_length - m_i < static_cast<ssize_t>(bytes)) return false;
+ memcpy(buf, &m_buffer[m_i], bytes);
+ m_i += bytes;
+ return true;
+ }
+ char *get_bytes(size_t number) {
+ if (m_length - m_i < static_cast<ssize_t>(number)) return NULL;
+ m_i += number;
+ return &m_buffer[m_i - number];
+ }
+};
+
+} // namespace aos
+
+#endif
+
diff --git a/aos/crio/shared_libs/interrupt_bridge-tmpl.h b/aos/crio/shared_libs/interrupt_bridge-tmpl.h
new file mode 100644
index 0000000..3adba38
--- /dev/null
+++ b/aos/crio/shared_libs/interrupt_bridge-tmpl.h
@@ -0,0 +1,243 @@
+#include <sysLib.h>
+#include <usrLib.h>
+#include <sigevent.h>
+
+#include "WPILib/Task.h"
+
+#include "aos/aos_core.h"
+#include "aos/crio/motor_server/MotorServer.h"
+#include "aos/common/time.h"
+
+extern "C" {
+// A really simple function implemented in a .c file because the header that
+// declares the variable doesn't work in C++.
+// Returns the value of the global variable excExtendedVectors declared by
+// <usrConfig.h>.
+int aos_getExcExtendedVectors();
+}
+
+namespace aos {
+namespace crio {
+
+// Conceptually a TimerNotifier*[]. Used by the signal handler so that it can
+// figure out which instance it's supposed to be using.
+// Doesn't need a lock because a value is put in here before the signal handler
+// is set up, so everything that might have concurrency issues will be reads
+// which will happen after the set to each index.
+// Declared like this instead of as an actual array because its size might be
+// determined dynamically (SIGRTMAX and SIGRTMIN can be function calls).
+extern void **const timer_notifiers;
+
+template<typename T>
+InterruptBridge<T>::InterruptBridge(Handler handler,
+ T *param, int priority)
+ : handler_(handler),
+ param_(param),
+ task_(new Task("_NotifierLooper", reinterpret_cast<FUNCPTR>(HandlerLoop),
+ priority)),
+ sem_(semBCreate(SEM_Q_PRIORITY, SEM_EMPTY)) {
+ // Basically, makes sure that it does -mlongcall for calling interrupt handler
+ // functions.
+ // See <http://www.vxdev.com/docs/vx55man/vxworks/ppc/powerpc.html#91321> for
+ // details about why this is important.
+ if (!aos_getExcExtendedVectors()) {
+ LOG(FATAL, "extended-call interrupts are not enabled\n");
+ }
+}
+
+template<typename T>
+InterruptBridge<T>::~InterruptBridge() {
+ // Can't call Stop() because that calls StopNotifications(), which is virtual,
+ // so you can't call it after the subclass's destructor has run.
+ semDelete(sem_);
+}
+
+template<typename T>
+void InterruptBridge<T>::StartTask() {
+ // The inner cast to InterruptBridge<T>* is so that Loop knows what to
+ // cast the void* to (the implementation of polymorphism means that
+ // casting the pointer might actually change its value).
+ task_->Start(reinterpret_cast<UINT32>(
+ static_cast<InterruptBridge<T> *>(this)));
+}
+
+template<typename T>
+void InterruptBridge<T>::Stop() {
+ StopNotifications();
+ task_->Stop();
+}
+
+template<typename T>
+void InterruptBridge<T>::HandlerLoop(void *self_in) {
+ InterruptBridge<T> *const self = static_cast<InterruptBridge<T> *>(self_in);
+ while (true) {
+ semTake(self->sem_, WAIT_FOREVER);
+ self->handler_(self->param_);
+ }
+}
+
+template<typename T>
+PeriodicNotifier<T>::PeriodicNotifier(
+ typename InterruptBridge<T>::Handler handler,
+ T *param, int priority)
+ : InterruptBridge<T>(handler, param, priority) {}
+
+template<typename T>
+void PeriodicNotifier<T>::StartPeriodic(double period) {
+ this->StartTask();
+ StartNotifications(period);
+}
+
+template<typename T>
+TimerNotifier<T>::TimerNotifier(typename InterruptBridge<T>::Handler handler,
+ T *param, int unique, int priority)
+ : PeriodicNotifier<T>(handler, param, priority),
+ signal_(SIGRTMIN + unique) {
+ timer_notifiers[signal_] = static_cast<void *>(this);
+
+ struct sigaction sa;
+ sa.sa_flags = 0;
+ sa.sa_handler = StaticNotify;
+ sigemptyset(&sa.sa_mask);
+ if (sigaction(signal_, &sa, &old_sa_) != OK) {
+ LOG(FATAL, "sigaction(%d, %p, %p) failed with %d: %s\n",
+ signal_, &sa, &old_sa_, errno, strerror(errno));
+ }
+
+ sigevent event;
+ event.sigev_notify = SIGEV_TASK_SIGNAL;
+ event.sigev_signo = signal_;
+ event.sigev_value.sival_ptr = this;
+ if (timer_create(CLOCK_REALTIME, &event, &timer_) != OK) {
+ LOG(FATAL, "timer_create(CLOCK_REALTIME, %p, %p) failed with %d: %s\n",
+ &event, &timer_, errno, strerror(errno));
+ }
+}
+
+template<typename T>
+TimerNotifier<T>::~TimerNotifier() {
+ if (timer_delete(timer_) != OK) {
+ LOG(FATAL, "timer_delete(%p) failed with %d: %s\n", timer_,
+ errno, strerror(errno));
+ }
+ if (sigaction(signal_, &old_sa_, NULL) != OK) {
+ LOG(FATAL, "sigaction(%d, %p, NULL) failed with %d: %s\n",
+ signal_, &old_sa_, errno, strerror(errno));
+ }
+ StopNotifications();
+}
+
+template<typename T>
+void TimerNotifier<T>::StartNotifications(double period) {
+ itimerspec timer_spec;
+ timer_spec.it_value.tv_sec = 0;
+ timer_spec.it_value.tv_nsec = 1; // 0 would mean to disarm the timer
+ timer_spec.it_interval = time::Time::InSeconds(period).ToTimespec();
+ if (timer_settime(timer_, 0, &timer_spec, NULL) != OK) {
+ LOG(FATAL, "timer_settime(%p, 0, %p, NULL) failed with %d: %s\n",
+ timer_, &timer_spec, errno, strerror(errno));
+ }
+}
+
+template<typename T>
+void TimerNotifier<T>::StopNotifications() {
+ timer_cancel(timer_);
+}
+
+template<typename T>
+WDInterruptNotifier<T>::WDInterruptNotifier(
+ typename InterruptBridge<T>::Handler handler, T *param, int priority)
+ : PeriodicNotifier<T>(handler, param, priority), wd_(wdCreate()) {
+ if (wd_ == NULL) {
+ LOG(FATAL, "wdCreate() failed with %d: %s\n", errno, strerror(errno));
+ }
+}
+
+template<typename T>
+WDInterruptNotifier<T>::~WDInterruptNotifier() {
+ if (wdDelete(wd_) != OK) {
+ LOG(FATAL, "wdDelete(%p) failed with %d: %s\n",
+ wd_, errno, strerror(errno));
+ }
+ StopNotifications();
+}
+
+template<typename T>
+void WDInterruptNotifier<T>::StartNotifications(double period) {
+ delay_ = time::Time::InSeconds(period).ToTicks();
+
+ if (wdStart(wd_,
+ 1, // run it really soon
+ (FUNCPTR)StaticNotify,
+ (UINT32)this) != OK) {
+ LOG(FATAL, "wdStart(%p) failed with %d: %s", wd_, errno, strerror(errno));
+ }
+}
+
+template<typename T>
+void WDInterruptNotifier<T>::StopNotifications() {
+ wdCancel(wd_);
+}
+
+// THESE GET CALLED AT INTERRUPT LEVEL. BE CAREFUL CHANGING THEM!!
+//
+// It might be tempting to use floating point math here, but DON'T!
+//
+// Also, do NOT use 64-bit integers (at least not without checking the assembly
+// code again). GCC optimizes those using the floating point registers (see
+// <http://compgroups.net/comp.os.vxworks/int64-where-gcc-ppc-and-vxworks-don-t-play-we/1110156>
+// for an example of that being a problem).
+//
+// The assembly code comments are in there to make looking at assembly code
+// dumps to verify that there aren't any floating point instructions easier.
+// brians did that on 10/14/12 to his then-uncommited code and didn't find any.
+// For future reference, here is a list of powerpc instruction mnemonics (what
+// g++ -S gives) that do not involve any floating point:
+// lwz
+// lis
+// mflr
+// la
+// stwu
+// stw
+// mr
+// mtctr
+// bctrl
+// addi
+// mtlr
+// blr
+// cmpwi
+// bne
+// li
+// NOTE: This macro is used in interrupt_notifier-tmpl.h too.
+#define ASM_COMMENT(str) __asm__("# " str)
+template<typename T>
+void WDInterruptNotifier<T>::StaticNotify(void *self_in) {
+ ASM_COMMENT("beginning of WDInterruptNotifier::StaticNotify");
+ WDInterruptNotifier<T> *const self =
+ static_cast<WDInterruptNotifier<T> *>(self_in);
+ wdStart(self->wd_,
+ self->delay_,
+ (FUNCPTR)StaticNotify,
+ (UINT32)self); // call the same thing again
+ self->Notify();
+ ASM_COMMENT("end of WDInterruptNotifier::StaticNotify");
+}
+
+template<typename T>
+void TimerNotifier<T>::StaticNotify(int signum) {
+ ASM_COMMENT("beginning of TimerNotifier::StaticNotify");
+ TimerNotifier<T> *const self =
+ static_cast<TimerNotifier<T> *>(timer_notifiers[signum]);
+ self->Notify();
+ ASM_COMMENT("end of TimerNotifier::StaticNotify");
+}
+
+template<typename T>
+void InterruptBridge<T>::Notify() {
+ ASM_COMMENT("beginning of InterruptBridge::Notify");
+ semGive(sem_);
+ ASM_COMMENT("end of InterruptBridge::Notify");
+}
+
+} // namespace crio
+} // namespace aos
diff --git a/aos/crio/shared_libs/interrupt_bridge.cc b/aos/crio/shared_libs/interrupt_bridge.cc
new file mode 100644
index 0000000..a905c55
--- /dev/null
+++ b/aos/crio/shared_libs/interrupt_bridge.cc
@@ -0,0 +1,9 @@
+#include "aos/crio/shared_libs/interrupt_bridge.h"
+
+namespace aos {
+namespace crio {
+
+void **const timer_notifiers = new void *[SIGRTMAX - SIGRTMIN];
+
+} // namespace crio
+} // namespace aos
diff --git a/aos/crio/shared_libs/interrupt_bridge.h b/aos/crio/shared_libs/interrupt_bridge.h
new file mode 100644
index 0000000..85ecd0f
--- /dev/null
+++ b/aos/crio/shared_libs/interrupt_bridge.h
@@ -0,0 +1,140 @@
+#ifndef AOS_CRIO_SHARED_LIBS_INTERRUPT_BRIDGE_H_
+#define AOS_CRIO_SHARED_LIBS_INTERRUPT_BRIDGE_H_
+
+#include <wdLib.h>
+#include <semLib.h>
+#include <timers.h>
+#include <signal.h>
+
+#include "aos/common/scoped_ptr.h"
+
+#include "aos/aos_core.h"
+
+class Task;
+
+namespace aos {
+namespace crio {
+
+// Handles creating a separate Task at a high priority with a semaphore to
+// link it to something else that provides timing information (likely in an ISR
+// context).
+template<typename T>
+class InterruptBridge {
+ public:
+ // The default priority. Here as a constant for subclasses to use as a default
+ // too.
+ static const int kDefaultPriority = 96;
+ typedef void (*Handler)(T *param);
+
+ // Stops calling the handler at all until a Start function is called again.
+ void Stop();
+
+ protected:
+ // < 95 priority does not work, and < 100 isn't guaranteed to work
+ InterruptBridge(Handler handler, T *param, int priority);
+ // Subclasses should call StopNotifications.
+ virtual ~InterruptBridge();
+
+ // Subclasses should call this whenever the Notifier triggers.
+ // It is safe to call from an ISR.
+ void Notify();
+ // Starts the actual Task.
+ void StartTask();
+
+ private:
+ const Handler handler_;
+ T *const param_;
+
+ // Subclasses should do whatever they have to to stop calling Notify().
+ virtual void StopNotifications() = 0;
+
+ // The function that the Task runs.
+ // Loops forever, waiting for sem_ and then calling handler_.
+ static void HandlerLoop(void *self_in);
+ const scoped_ptr<Task> task_;
+ // For synchronizing between the Task and Notify().
+ SEM_ID sem_;
+ DISALLOW_COPY_AND_ASSIGN(InterruptBridge<T>);
+};
+
+// An accurate version of WPILib's Notifier class.
+template<typename T>
+class PeriodicNotifier : public InterruptBridge<T> {
+ public:
+ // Period is how much (in seconds) to wait between running the handler.
+ void StartPeriodic(double period);
+
+ protected:
+ PeriodicNotifier(typename InterruptBridge<T>::Handler handler, T *param,
+ int priority);
+ virtual ~PeriodicNotifier() {}
+
+ private:
+ virtual void StopNotifications() = 0;
+ // Subclasses should do whatever they have to to start calling Notify() every
+ // period seconds.
+ virtual void StartNotifications(double period) = 0;
+};
+
+// This one works accurately, but it has the potential to drift over time.
+// It has only sysClockRateGet() resolution.
+template<typename T>
+class WDInterruptNotifier : public PeriodicNotifier<T> {
+ public:
+ WDInterruptNotifier(typename InterruptBridge<T>::Handler handler,
+ T *param = NULL,
+ int priority = InterruptBridge<T>::kDefaultPriority);
+ virtual ~WDInterruptNotifier();
+
+ private:
+ // The argument is the general callback parameter which will be a pointer to
+ // an instance. This function calls Notify() on that instance.
+ static void StaticNotify(void *self_in);
+ virtual void StopNotifications();
+ virtual void StartNotifications(double period);
+
+ WDOG_ID wd_;
+ int delay_; // what to pass to wdStart
+ DISALLOW_COPY_AND_ASSIGN(WDInterruptNotifier<T>);
+};
+
+// Vxworks (really really) should take care of making sure that this one
+// doesn't drift over time, but IT DOESN'T!! Brian found the implementation
+// online (file timerLib.c), and it's just doing the same thing as
+// WDInterruptNotifier, except with extra conversions and overhead to implement
+// the POSIX standard. There really is no reason to use this.
+// It has only sysClockRateGet() resolution.
+template<typename T>
+class TimerNotifier : public PeriodicNotifier<T> {
+ public:
+ // unique should be different for all instances created in the same Task. It
+ // can range from 0 to (SIGRTMAX - SIGRTMIN). This instance will use the
+ // signal (SIGRTMIN + unique), so nothing else should use that signal.
+ TimerNotifier(typename InterruptBridge<T>::Handler handler,
+ T *param = NULL,
+ int unique = 0,
+ int priority = InterruptBridge<T>::kDefaultPriority);
+ virtual ~TimerNotifier();
+
+ private:
+ // The first argument is the signal number that is being triggered. This
+ // function looks up a pointer to an instance in timer_notifiers using that
+ // and calls Notify() on that instance.
+ static void StaticNotify(int signum);
+ virtual void StopNotifications();
+ virtual void StartNotifications(double period);
+
+ timer_t timer_;
+ // Which signal timer_ will notify on.
+ const int signal_;
+ // What the action for signal_ was before we started messing with it.
+ struct sigaction old_sa_;
+ DISALLOW_COPY_AND_ASSIGN(TimerNotifier<T>);
+};
+
+} // namespace crio
+} // namespace aos
+
+#include "aos/crio/shared_libs/interrupt_bridge-tmpl.h"
+
+#endif // AOS_CRIO_SHARED_LIBS_INTERRUPT_BRIDGE_H_
diff --git a/aos/crio/shared_libs/interrupt_bridge_c.c b/aos/crio/shared_libs/interrupt_bridge_c.c
new file mode 100644
index 0000000..7a74ea1
--- /dev/null
+++ b/aos/crio/shared_libs/interrupt_bridge_c.c
@@ -0,0 +1,9 @@
+#include <vxWorksCommon.h> // or else it blows up...
+// This header ends up trying to #include a header which declares a struct with
+// a member named "delete". This means that it can not be used from code
+// compiled with the C++ compiler.
+#include <usrConfig.h>
+
+int aos_getExcExtendedVectors(void) {
+ return excExtendedVectors;
+}
diff --git a/aos/crio/shared_libs/interrupt_bridge_demo.cc b/aos/crio/shared_libs/interrupt_bridge_demo.cc
new file mode 100644
index 0000000..d7e66be
--- /dev/null
+++ b/aos/crio/shared_libs/interrupt_bridge_demo.cc
@@ -0,0 +1,45 @@
+#include "aos/crio/shared_libs/interrupt_bridge.h"
+
+#include <unistd.h>
+
+#include "WPILib/Timer.h"
+
+#include "aos/aos_core.h"
+#include "aos/common/time.h"
+
+using aos::time::Time;
+
+namespace aos {
+namespace crio {
+
+class InterruptBridgeTest {
+ public:
+ void Run(double seconds) {
+ int interruptVal = 1;
+ WDInterruptNotifier<int> interrupt(Notify, &interruptVal);
+ interrupt.StartPeriodic(0.01);
+ int timerVal = 2;
+ TimerNotifier<int> timer(Notify, &timerVal);
+ time::SleepFor(Time::InSeconds(0.005)); // get them offset by ~180 degrees
+ timer.StartPeriodic(0.01);
+ time::SleepFor(Time::InSeconds(seconds));
+ }
+ private:
+ static void Notify(int *value) {
+ printf("notified %f,%d\n", Timer::GetFPGATimestamp(), *value);
+ }
+};
+
+} // namespace crio
+} // namespace aos
+
+// Designed to be called from the vxworks shell if somebody wants to run this.
+extern "C" int interrupt_bridge_demo(int seconds) {
+ if (seconds == 0) {
+ printf("arguments: number of seconds\n");
+ return -1;
+ }
+ aos::crio::InterruptBridgeTest runner;
+ runner.Run(seconds);
+ return 0;
+}
diff --git a/aos/crio/shared_libs/interrupt_notifier-tmpl.h b/aos/crio/shared_libs/interrupt_notifier-tmpl.h
new file mode 100644
index 0000000..78e7ca8
--- /dev/null
+++ b/aos/crio/shared_libs/interrupt_notifier-tmpl.h
@@ -0,0 +1,48 @@
+#include <intLib.h>
+#include <logLib.h>
+
+namespace aos {
+namespace crio {
+
+template<typename T>
+InterruptNotifier<T>::InterruptNotifier(
+ typename InterruptBridge<T>::Handler handler,
+ InterruptableSensorBase *sensor, T *param, int priority)
+ : InterruptBridge<T>(handler, param, priority), sensor_(sensor) {
+ sensor_->RequestInterrupts(StaticNotify, this);
+}
+
+template<typename T>
+InterruptNotifier<T>::~InterruptNotifier() {
+ sensor_->CancelInterrupts();
+}
+
+template<typename T>
+void InterruptNotifier<T>::Start() {
+ this->StartTask();
+ sensor_->EnableInterrupts();
+}
+
+template<typename T>
+void InterruptNotifier<T>::StopNotifications() {
+ sensor_->DisableInterrupts();
+}
+
+// WARNING: This IS called from an ISR. Don't use floating point. Look in
+// interrupt_bridge-tmpl.h for details.
+template<typename T>
+void InterruptNotifier<T>::StaticNotify(uint32_t, void *self_in) {
+ ASM_COMMENT("beginning of InterruptNotifier::StaticNotify");
+ if (!intContext()) { // if we're not in an actual ISR
+ logMsg(const_cast<char *>("WPILib is not calling callbacks"
+ " in actual ISRs any more!!\n"),
+ 0, 0, 0, 0, 0, 0);
+ }
+ InterruptNotifier<T> *const self =
+ static_cast<InterruptNotifier<T> *>(self_in);
+ self->Notify();
+ ASM_COMMENT("end of InterruptNotifier::StaticNotify");
+}
+
+} // namespace crio
+} // namespace aos
diff --git a/aos/crio/shared_libs/interrupt_notifier.h b/aos/crio/shared_libs/interrupt_notifier.h
new file mode 100644
index 0000000..87aa4a3
--- /dev/null
+++ b/aos/crio/shared_libs/interrupt_notifier.h
@@ -0,0 +1,49 @@
+#ifndef AOS_CRIO_SHARED_LIBS_INTERRUPT_NOTIFIER_H_
+#define AOS_CRIO_SHARED_LIBS_INTERRUPT_NOTIFIER_H_
+
+#include "WPILib/InterruptableSensorBase.h"
+
+#include "aos/crio/shared_libs/interrupt_bridge.h"
+
+namespace aos {
+namespace crio {
+
+// An InterruptBridge that notifies based on interrupts from a WPILib
+// InterruptableSensorBase object (which DigitalInput is an example of).
+template<typename T>
+class InterruptNotifier : public InterruptBridge<T> {
+ public:
+ // This object will hold a reference to sensor, but will not free it. This
+ // object will take ownership of everything related to interrupts for sensor
+ // (ie this constructor will call sensor->RequestInterrupts).
+ // Interrupts should be cancelled (the state InterruptableSensorBases are
+ // constructed in) when this constructor is called.
+ // Any setup of sensor that is required should happen before Start() is
+ // called, but after this constructor (ie SetUpSourceEdge).
+ InterruptNotifier(typename InterruptBridge<T>::Handler handler,
+ InterruptableSensorBase *sensor,
+ T *param = NULL,
+ int priority = InterruptBridge<T>::kDefaultPriority);
+ virtual ~InterruptNotifier();
+
+ // Starts calling the handler whenever the interrupt triggers.
+ void Start();
+
+ private:
+ // The only docs that seem to exist on the first arg is that it's named
+ // interruptAssertedMask in WPILib/ChipObject/tInterruptManager.h
+ // The second arg is the general callback parameter which will be a pointer to
+ // an instance. This function calls Notify() on that instance.
+ static void StaticNotify(uint32_t, void *self_in);
+ virtual void StopNotifications();
+
+ InterruptableSensorBase *const sensor_;
+ DISALLOW_COPY_AND_ASSIGN(InterruptNotifier<T>);
+};
+
+} // namespace crio
+} // namespace aos
+
+#include "aos/crio/shared_libs/interrupt_notifier-tmpl.h"
+
+#endif // AOS_CRIO_SHARED_LIBS_INTERRUPT_NOTIFIER_H_
diff --git a/aos/crio/shared_libs/mutex.cpp b/aos/crio/shared_libs/mutex.cpp
new file mode 100644
index 0000000..35ac4e3
--- /dev/null
+++ b/aos/crio/shared_libs/mutex.cpp
@@ -0,0 +1,48 @@
+#include "aos/common/mutex.h"
+
+#include <semLib.h>
+
+namespace aos {
+
+Mutex::Mutex() : impl_(semBCreate(SEM_Q_PRIORITY, SEM_FULL)) {
+ if (impl_ == NULL) {
+ LOG(FATAL,
+ "semBCreate(SEM_Q_PRIORITY, SEM_FULL) failed because of %d: %s\n",
+ errno, strerror(errno));
+ }
+}
+
+Mutex::~Mutex() {
+ if (semDelete(impl_) != 0) {
+ LOG(FATAL, "semDelete(%p) failed because of %d: %s\n",
+ impl_, errno, strerror(errno));
+ }
+}
+
+void Mutex::Lock() {
+ if (semTake(impl_, WAIT_FOREVER) != 0) {
+ LOG(FATAL, "semTake(%p, WAIT_FOREVER) failed because of %d: %s\n",
+ impl_, errno, strerror(errno));
+ }
+}
+
+void Mutex::Unlock() {
+ if (semGive(impl_) != 0) {
+ LOG(FATAL, "semGive(%p) failed because of %d: %s\n",
+ impl_, errno, strerror(errno));
+ }
+}
+
+bool Mutex::TryLock() {
+ if (semTake(impl_, NO_WAIT) == 0) {
+ return true;
+ }
+ // The semLib documention is wrong about what the errno will be.
+ if (errno != S_objLib_OBJ_UNAVAILABLE) {
+ LOG(FATAL, "semTake(%p, WAIT_FOREVER) failed because of %d: %s\n",
+ impl_, errno, strerror(errno));
+ }
+ return false;
+}
+
+} // namespace aos
diff --git a/aos/crio/type_traits/tr1_impl/type_traits b/aos/crio/type_traits/tr1_impl/type_traits
new file mode 100644
index 0000000..47f5e8f
--- /dev/null
+++ b/aos/crio/type_traits/tr1_impl/type_traits
@@ -0,0 +1,502 @@
+// TR1 type_traits -*- C++ -*-
+
+// Copyright (C) 2007, 2008, 2009 Free Software Foundation, Inc.
+//
+// This file is part of the GNU ISO C++ Library. This library is free
+// software; you can redistribute it and/or modify it under the
+// terms of the GNU General Public License as published by the
+// Free Software Foundation; either version 3, or (at your option)
+// any later version.
+
+// This library is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+
+// Under Section 7 of GPL version 3, you are granted additional
+// permissions described in the GCC Runtime Library Exception, version
+// 3.1, as published by the Free Software Foundation.
+
+// You should have received a copy of the GNU General Public License and
+// a copy of the GCC Runtime Library Exception along with this program;
+// see the files COPYING3 and COPYING.RUNTIME respectively. If not, see
+// <http://www.gnu.org/licenses/>.
+
+/** @file tr1_impl/type_traits
+* This is an internal header file, included by other library headers.
+* You should not attempt to use it directly.
+*/
+
+namespace std
+{
+_GLIBCXX_BEGIN_NAMESPACE_TR1
+
+ /**
+ * @defgroup metaprogramming Type Traits
+ * @ingroup utilities
+ *
+ * Compile time type transformation and information.
+ * @{
+ */
+
+ // For use in __is_convertible_simple.
+ struct __sfinae_types
+ {
+ typedef char __one;
+ typedef struct { char __arr[2]; } __two;
+ };
+
+#define _DEFINE_SPEC_0_HELPER \
+ template<>
+
+#define _DEFINE_SPEC_1_HELPER \
+ template<typename _Tp>
+
+#define _DEFINE_SPEC_2_HELPER \
+ template<typename _Tp, typename _Cp>
+
+#define _DEFINE_SPEC(_Order, _Trait, _Type, _Value) \
+ _DEFINE_SPEC_##_Order##_HELPER \
+ struct _Trait<_Type> \
+ : public integral_constant<bool, _Value> { };
+
+ // helper classes [4.3].
+
+ /// integral_constant
+ template<typename _Tp, _Tp __v>
+ struct integral_constant
+ {
+ static const _Tp value = __v;
+ typedef _Tp value_type;
+ typedef integral_constant<_Tp, __v> type;
+ };
+
+ /// typedef for true_type
+ typedef integral_constant<bool, true> true_type;
+
+ /// typedef for false_type
+ typedef integral_constant<bool, false> false_type;
+
+ template<typename _Tp, _Tp __v>
+ const _Tp integral_constant<_Tp, __v>::value;
+
+ /// remove_cv
+ template<typename>
+ struct remove_cv;
+
+ template<typename>
+ struct __is_void_helper
+ : public false_type { };
+ _DEFINE_SPEC(0, __is_void_helper, void, true)
+
+ // primary type categories [4.5.1].
+
+ /// is_void
+ template<typename _Tp>
+ struct is_void
+ : public integral_constant<bool, (__is_void_helper<typename
+ remove_cv<_Tp>::type>::value)>
+ { };
+
+ template<typename>
+ struct __is_integral_helper
+ : public false_type { };
+ _DEFINE_SPEC(0, __is_integral_helper, bool, true)
+ _DEFINE_SPEC(0, __is_integral_helper, char, true)
+ _DEFINE_SPEC(0, __is_integral_helper, signed char, true)
+ _DEFINE_SPEC(0, __is_integral_helper, unsigned char, true)
+#ifdef _GLIBCXX_USE_WCHAR_T
+ _DEFINE_SPEC(0, __is_integral_helper, wchar_t, true)
+#endif
+#ifdef _GLIBCXX_INCLUDE_AS_CXX0X
+ _DEFINE_SPEC(0, __is_integral_helper, char16_t, true)
+ _DEFINE_SPEC(0, __is_integral_helper, char32_t, true)
+#endif
+ _DEFINE_SPEC(0, __is_integral_helper, short, true)
+ _DEFINE_SPEC(0, __is_integral_helper, unsigned short, true)
+ _DEFINE_SPEC(0, __is_integral_helper, int, true)
+ _DEFINE_SPEC(0, __is_integral_helper, unsigned int, true)
+ _DEFINE_SPEC(0, __is_integral_helper, long, true)
+ _DEFINE_SPEC(0, __is_integral_helper, unsigned long, true)
+ _DEFINE_SPEC(0, __is_integral_helper, long long, true)
+ _DEFINE_SPEC(0, __is_integral_helper, unsigned long long, true)
+
+ /// is_integral
+ template<typename _Tp>
+ struct is_integral
+ : public integral_constant<bool, (__is_integral_helper<typename
+ remove_cv<_Tp>::type>::value)>
+ { };
+
+ template<typename>
+ struct __is_floating_point_helper
+ : public false_type { };
+ _DEFINE_SPEC(0, __is_floating_point_helper, float, true)
+ _DEFINE_SPEC(0, __is_floating_point_helper, double, true)
+ _DEFINE_SPEC(0, __is_floating_point_helper, long double, true)
+
+ /// is_floating_point
+ template<typename _Tp>
+ struct is_floating_point
+ : public integral_constant<bool, (__is_floating_point_helper<typename
+ remove_cv<_Tp>::type>::value)>
+ { };
+
+ /// is_array
+ template<typename>
+ struct is_array
+ : public false_type { };
+
+ template<typename _Tp, std::size_t _Size>
+ struct is_array<_Tp[_Size]>
+ : public true_type { };
+
+ template<typename _Tp>
+ struct is_array<_Tp[]>
+ : public true_type { };
+
+ template<typename>
+ struct __is_pointer_helper
+ : public false_type { };
+ _DEFINE_SPEC(1, __is_pointer_helper, _Tp*, true)
+
+ /// is_pointer
+ template<typename _Tp>
+ struct is_pointer
+ : public integral_constant<bool, (__is_pointer_helper<typename
+ remove_cv<_Tp>::type>::value)>
+ { };
+
+ /// is_reference
+ template<typename _Tp>
+ struct is_reference;
+
+ /// is_function
+ template<typename _Tp>
+ struct is_function;
+
+ template<typename>
+ struct __is_member_object_pointer_helper
+ : public false_type { };
+ _DEFINE_SPEC(2, __is_member_object_pointer_helper, _Tp _Cp::*,
+ !is_function<_Tp>::value)
+
+ /// is_member_object_pointer
+ template<typename _Tp>
+ struct is_member_object_pointer
+ : public integral_constant<bool, (__is_member_object_pointer_helper<
+ typename remove_cv<_Tp>::type>::value)>
+ { };
+
+ template<typename>
+ struct __is_member_function_pointer_helper
+ : public false_type { };
+ _DEFINE_SPEC(2, __is_member_function_pointer_helper, _Tp _Cp::*,
+ is_function<_Tp>::value)
+
+ /// is_member_function_pointer
+ template<typename _Tp>
+ struct is_member_function_pointer
+ : public integral_constant<bool, (__is_member_function_pointer_helper<
+ typename remove_cv<_Tp>::type>::value)>
+ { };
+
+ /// is_enum
+ template<typename _Tp>
+ struct is_enum
+ : public integral_constant<bool, __is_enum(_Tp)>
+ { };
+
+ /// is_union
+ template<typename _Tp>
+ struct is_union
+ : public integral_constant<bool, __is_union(_Tp)>
+ { };
+
+ /// is_class
+ template<typename _Tp>
+ struct is_class
+ : public integral_constant<bool, __is_class(_Tp)>
+ { };
+
+ /// is_function
+ template<typename>
+ struct is_function
+ : public false_type { };
+ template<typename _Res, typename... _ArgTypes>
+ struct is_function<_Res(_ArgTypes...)>
+ : public true_type { };
+ template<typename _Res, typename... _ArgTypes>
+ struct is_function<_Res(_ArgTypes......)>
+ : public true_type { };
+ template<typename _Res, typename... _ArgTypes>
+ struct is_function<_Res(_ArgTypes...) const>
+ : public true_type { };
+ template<typename _Res, typename... _ArgTypes>
+ struct is_function<_Res(_ArgTypes......) const>
+ : public true_type { };
+ template<typename _Res, typename... _ArgTypes>
+ struct is_function<_Res(_ArgTypes...) volatile>
+ : public true_type { };
+ template<typename _Res, typename... _ArgTypes>
+ struct is_function<_Res(_ArgTypes......) volatile>
+ : public true_type { };
+ template<typename _Res, typename... _ArgTypes>
+ struct is_function<_Res(_ArgTypes...) const volatile>
+ : public true_type { };
+ template<typename _Res, typename... _ArgTypes>
+ struct is_function<_Res(_ArgTypes......) const volatile>
+ : public true_type { };
+
+ // composite type traits [4.5.2].
+
+ /// is_arithmetic
+ template<typename _Tp>
+ struct is_arithmetic
+ : public integral_constant<bool, (is_integral<_Tp>::value
+ || is_floating_point<_Tp>::value)>
+ { };
+
+ /// is_fundamental
+ template<typename _Tp>
+ struct is_fundamental
+ : public integral_constant<bool, (is_arithmetic<_Tp>::value
+ || is_void<_Tp>::value)>
+ { };
+
+ /// is_object
+ template<typename _Tp>
+ struct is_object
+ : public integral_constant<bool, !(is_function<_Tp>::value
+ || is_reference<_Tp>::value
+ || is_void<_Tp>::value)>
+ { };
+
+ /// is_member_pointer
+ template<typename _Tp>
+ struct is_member_pointer;
+
+ /// is_scalar
+ template<typename _Tp>
+ struct is_scalar
+ : public integral_constant<bool, (is_arithmetic<_Tp>::value
+ || is_enum<_Tp>::value
+ || is_pointer<_Tp>::value
+ || is_member_pointer<_Tp>::value)>
+ { };
+
+ /// is_compound
+ template<typename _Tp>
+ struct is_compound
+ : public integral_constant<bool, !is_fundamental<_Tp>::value> { };
+
+ /// is_member_pointer
+ template<typename _Tp>
+ struct __is_member_pointer_helper
+ : public false_type { };
+ _DEFINE_SPEC(2, __is_member_pointer_helper, _Tp _Cp::*, true)
+
+ template<typename _Tp>
+ struct is_member_pointer
+ : public integral_constant<bool, (__is_member_pointer_helper<
+ typename remove_cv<_Tp>::type>::value)>
+ { };
+
+ // type properties [4.5.3].
+ /// is_const
+ template<typename>
+ struct is_const
+ : public false_type { };
+
+ template<typename _Tp>
+ struct is_const<_Tp const>
+ : public true_type { };
+
+ /// is_volatile
+ template<typename>
+ struct is_volatile
+ : public false_type { };
+
+ template<typename _Tp>
+ struct is_volatile<_Tp volatile>
+ : public true_type { };
+
+ /// is_empty
+ template<typename _Tp>
+ struct is_empty
+ : public integral_constant<bool, __is_empty(_Tp)>
+ { };
+
+ /// is_polymorphic
+ template<typename _Tp>
+ struct is_polymorphic
+ : public integral_constant<bool, __is_polymorphic(_Tp)>
+ { };
+
+ /// is_abstract
+ template<typename _Tp>
+ struct is_abstract
+ : public integral_constant<bool, __is_abstract(_Tp)>
+ { };
+
+ /// has_virtual_destructor
+ template<typename _Tp>
+ struct has_virtual_destructor
+ : public integral_constant<bool, __has_virtual_destructor(_Tp)>
+ { };
+
+ /// alignment_of
+ template<typename _Tp>
+ struct alignment_of
+ : public integral_constant<std::size_t, __alignof__(_Tp)> { };
+
+ /// rank
+ template<typename>
+ struct rank
+ : public integral_constant<std::size_t, 0> { };
+
+ template<typename _Tp, std::size_t _Size>
+ struct rank<_Tp[_Size]>
+ : public integral_constant<std::size_t, 1 + rank<_Tp>::value> { };
+
+ template<typename _Tp>
+ struct rank<_Tp[]>
+ : public integral_constant<std::size_t, 1 + rank<_Tp>::value> { };
+
+ /// extent
+ template<typename, unsigned _Uint = 0>
+ struct extent
+ : public integral_constant<std::size_t, 0> { };
+
+ template<typename _Tp, unsigned _Uint, std::size_t _Size>
+ struct extent<_Tp[_Size], _Uint>
+ : public integral_constant<std::size_t,
+ _Uint == 0 ? _Size : extent<_Tp,
+ _Uint - 1>::value>
+ { };
+
+ template<typename _Tp, unsigned _Uint>
+ struct extent<_Tp[], _Uint>
+ : public integral_constant<std::size_t,
+ _Uint == 0 ? 0 : extent<_Tp,
+ _Uint - 1>::value>
+ { };
+
+ // relationships between types [4.6].
+
+ /// is_same
+ template<typename, typename>
+ struct is_same
+ : public false_type { };
+
+ template<typename _Tp>
+ struct is_same<_Tp, _Tp>
+ : public true_type { };
+
+ // const-volatile modifications [4.7.1].
+
+ /// remove_const
+ template<typename _Tp>
+ struct remove_const
+ { typedef _Tp type; };
+
+ template<typename _Tp>
+ struct remove_const<_Tp const>
+ { typedef _Tp type; };
+
+ /// remove_volatile
+ template<typename _Tp>
+ struct remove_volatile
+ { typedef _Tp type; };
+
+ template<typename _Tp>
+ struct remove_volatile<_Tp volatile>
+ { typedef _Tp type; };
+
+ /// remove_cv
+ template<typename _Tp>
+ struct remove_cv
+ {
+ typedef typename
+ remove_const<typename remove_volatile<_Tp>::type>::type type;
+ };
+
+ /// add_const
+ template<typename _Tp>
+ struct add_const
+ { typedef _Tp const type; };
+
+ /// add_volatile
+ template<typename _Tp>
+ struct add_volatile
+ { typedef _Tp volatile type; };
+
+ /// add_cv
+ template<typename _Tp>
+ struct add_cv
+ {
+ typedef typename
+ add_const<typename add_volatile<_Tp>::type>::type type;
+ };
+
+ // array modifications [4.7.3].
+
+ /// remove_extent
+ template<typename _Tp>
+ struct remove_extent
+ { typedef _Tp type; };
+
+ template<typename _Tp, std::size_t _Size>
+ struct remove_extent<_Tp[_Size]>
+ { typedef _Tp type; };
+
+ template<typename _Tp>
+ struct remove_extent<_Tp[]>
+ { typedef _Tp type; };
+
+ /// remove_all_extents
+ template<typename _Tp>
+ struct remove_all_extents
+ { typedef _Tp type; };
+
+ template<typename _Tp, std::size_t _Size>
+ struct remove_all_extents<_Tp[_Size]>
+ { typedef typename remove_all_extents<_Tp>::type type; };
+
+ template<typename _Tp>
+ struct remove_all_extents<_Tp[]>
+ { typedef typename remove_all_extents<_Tp>::type type; };
+
+ // pointer modifications [4.7.4].
+
+ template<typename _Tp, typename>
+ struct __remove_pointer_helper
+ { typedef _Tp type; };
+
+ template<typename _Tp, typename _Up>
+ struct __remove_pointer_helper<_Tp, _Up*>
+ { typedef _Up type; };
+
+ /// remove_pointer
+ template<typename _Tp>
+ struct remove_pointer
+ : public __remove_pointer_helper<_Tp, typename remove_cv<_Tp>::type>
+ { };
+
+ template<typename>
+ struct remove_reference;
+
+ /// add_pointer
+ template<typename _Tp>
+ struct add_pointer
+ { typedef typename remove_reference<_Tp>::type* type; };
+
+#undef _DEFINE_SPEC_0_HELPER
+#undef _DEFINE_SPEC_1_HELPER
+#undef _DEFINE_SPEC_2_HELPER
+#undef _DEFINE_SPEC
+
+ // @} group metaprogramming
+
+_GLIBCXX_END_NAMESPACE_TR1
+}
diff --git a/aos/crio/type_traits/type_traits b/aos/crio/type_traits/type_traits
new file mode 100644
index 0000000..afef722
--- /dev/null
+++ b/aos/crio/type_traits/type_traits
@@ -0,0 +1,634 @@
+// C++0x type_traits -*- C++ -*-
+
+// Copyright (C) 2007, 2008, 2009, 2010 Free Software Foundation, Inc.
+//
+// This file is part of the GNU ISO C++ Library. This library is free
+// software; you can redistribute it and/or modify it under the
+// terms of the GNU General Public License as published by the
+// Free Software Foundation; either version 3, or (at your option)
+// any later version.
+
+// This library is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+
+// Under Section 7 of GPL version 3, you are granted additional
+// permissions described in the GCC Runtime Library Exception, version
+// 3.1, as published by the Free Software Foundation.
+
+// You should have received a copy of the GNU General Public License and
+// a copy of the GCC Runtime Library Exception along with this program;
+// see the files COPYING3 and COPYING.RUNTIME respectively. If not, see
+// <http://www.gnu.org/licenses/>.
+
+/** @file include/type_traits
+ * This is a Standard C++ Library header.
+ */
+
+#ifndef _GLIBCXX_TYPE_TRAITS
+#define _GLIBCXX_TYPE_TRAITS 1
+
+#pragma GCC system_header
+
+#ifndef __GXX_EXPERIMENTAL_CXX0X__
+# include <bits/c++0x_warning.h>
+#else
+
+#if defined(_GLIBCXX_INCLUDE_AS_TR1)
+# error C++0x header cannot be included from TR1 header
+#endif
+
+#include <cstddef>
+
+#if defined(_GLIBCXX_INCLUDE_AS_CXX0X)
+# include "aos/crio/type_traits/tr1_impl/type_traits"
+#else
+# define _GLIBCXX_INCLUDE_AS_CXX0X
+# define _GLIBCXX_BEGIN_NAMESPACE_TR1
+# define _GLIBCXX_END_NAMESPACE_TR1
+# define _GLIBCXX_TR1
+# include "aos/crio/type_traits/tr1_impl/type_traits"
+# undef _GLIBCXX_TR1
+# undef _GLIBCXX_END_NAMESPACE_TR1
+# undef _GLIBCXX_BEGIN_NAMESPACE_TR1
+# undef _GLIBCXX_INCLUDE_AS_CXX0X
+#endif
+
+namespace std
+{
+ /**
+ * @addtogroup metaprogramming
+ * @{
+ */
+
+ // Primary classification traits.
+
+ /// is_lvalue_reference
+ template<typename>
+ struct is_lvalue_reference
+ : public false_type { };
+
+ template<typename _Tp>
+ struct is_lvalue_reference<_Tp&>
+ : public true_type { };
+
+ /// is_rvalue_reference
+ template<typename>
+ struct is_rvalue_reference
+ : public false_type { };
+
+ template<typename _Tp>
+ struct is_rvalue_reference<_Tp&&>
+ : public true_type { };
+
+ // Secondary classification traits.
+
+ /// is_reference
+ template<typename _Tp>
+ struct is_reference
+ : public integral_constant<bool, (is_lvalue_reference<_Tp>::value
+ || is_rvalue_reference<_Tp>::value)>
+ { };
+
+ // Reference transformations.
+
+ /// remove_reference
+ template<typename _Tp>
+ struct remove_reference
+ { typedef _Tp type; };
+
+ template<typename _Tp>
+ struct remove_reference<_Tp&>
+ { typedef _Tp type; };
+
+ template<typename _Tp>
+ struct remove_reference<_Tp&&>
+ { typedef _Tp type; };
+
+ template<typename _Tp,
+ bool = !is_reference<_Tp>::value && !is_void<_Tp>::value,
+ bool = is_rvalue_reference<_Tp>::value>
+ struct __add_lvalue_reference_helper
+ { typedef _Tp type; };
+
+ template<typename _Tp>
+ struct __add_lvalue_reference_helper<_Tp, true, false>
+ { typedef _Tp& type; };
+
+ template<typename _Tp>
+ struct __add_lvalue_reference_helper<_Tp, false, true>
+ { typedef typename remove_reference<_Tp>::type& type; };
+
+ /// add_lvalue_reference
+ template<typename _Tp>
+ struct add_lvalue_reference
+ : public __add_lvalue_reference_helper<_Tp>
+ { };
+
+ template<typename _Tp,
+ bool = !is_reference<_Tp>::value && !is_void<_Tp>::value>
+ struct __add_rvalue_reference_helper
+ { typedef _Tp type; };
+
+ template<typename _Tp>
+ struct __add_rvalue_reference_helper<_Tp, true>
+ { typedef _Tp&& type; };
+
+ /// add_rvalue_reference
+ template<typename _Tp>
+ struct add_rvalue_reference
+ : public __add_rvalue_reference_helper<_Tp>
+ { };
+
+ // Scalar properties and transformations.
+
+ template<typename _Tp,
+ bool = is_integral<_Tp>::value,
+ bool = is_floating_point<_Tp>::value>
+ struct __is_signed_helper
+ : public false_type { };
+
+ template<typename _Tp>
+ struct __is_signed_helper<_Tp, false, true>
+ : public true_type { };
+
+ template<typename _Tp>
+ struct __is_signed_helper<_Tp, true, false>
+ : public integral_constant<bool, static_cast<bool>(_Tp(-1) < _Tp(0))>
+ { };
+
+ /// is_signed
+ template<typename _Tp>
+ struct is_signed
+ : public integral_constant<bool, __is_signed_helper<_Tp>::value>
+ { };
+
+ /// is_unsigned
+ template<typename _Tp>
+ struct is_unsigned
+ : public integral_constant<bool, (is_arithmetic<_Tp>::value
+ && !is_signed<_Tp>::value)>
+ { };
+
+ // Member introspection.
+
+ /// is_trivial
+ template<typename _Tp>
+ struct is_trivial
+ : public integral_constant<bool, __is_trivial(_Tp)>
+ { };
+
+ /// is_standard_layout
+ template<typename _Tp>
+ struct is_standard_layout
+ : public integral_constant<bool, __is_standard_layout(_Tp)>
+ { };
+
+ /// is_pod
+ // Could use is_standard_layout && is_trivial instead of the builtin.
+ template<typename _Tp>
+ struct is_pod
+ : public integral_constant<bool, __is_pod(_Tp)>
+ { };
+
+ template<typename _Tp>
+ typename add_rvalue_reference<_Tp>::type declval();
+
+ template<typename _Tp, typename... _Args>
+ class __is_constructible_helper
+ : public __sfinae_types
+ {
+ template<typename _Tp1, typename... _Args1>
+ static decltype(_Tp1(declval<_Args1>()...), __one()) __test(int);
+
+ template<typename, typename...>
+ static __two __test(...);
+
+ public:
+ static const bool __value = sizeof(__test<_Tp, _Args...>(0)) == 1;
+ };
+
+ template<typename _Tp, typename _Arg>
+ class __is_constructible_helper<_Tp, _Arg>
+ : public __sfinae_types
+ {
+ template<typename _Tp1, typename _Arg1>
+ static decltype(static_cast<_Tp1>(declval<_Arg1>()), __one())
+ __test(int);
+
+ template<typename, typename>
+ static __two __test(...);
+
+ public:
+ static const bool __value = sizeof(__test<_Tp, _Arg>(0)) == 1;
+ };
+
+ /// is_constructible
+ // XXX FIXME
+ // The C++0x specifications require front-end support, see N2255.
+ template<typename _Tp, typename... _Args>
+ struct is_constructible
+ : public integral_constant<bool,
+ __is_constructible_helper<_Tp,
+ _Args...>::__value>
+ { };
+
+ /// has_trivial_default_constructor
+ template<typename _Tp>
+ struct has_trivial_default_constructor
+ : public integral_constant<bool, __has_trivial_constructor(_Tp)>
+ { };
+
+ /// has_trivial_copy_constructor
+ template<typename _Tp>
+ struct has_trivial_copy_constructor
+ : public integral_constant<bool, __has_trivial_copy(_Tp)>
+ { };
+
+ /// has_trivial_assign
+ template<typename _Tp>
+ struct has_trivial_assign
+ : public integral_constant<bool, __has_trivial_assign(_Tp)>
+ { };
+
+ /// has_trivial_destructor
+ template<typename _Tp>
+ struct has_trivial_destructor
+ : public integral_constant<bool, __has_trivial_destructor(_Tp)>
+ { };
+
+ /// has_nothrow_default_constructor
+ template<typename _Tp>
+ struct has_nothrow_default_constructor
+ : public integral_constant<bool, __has_nothrow_constructor(_Tp)>
+ { };
+
+ /// has_nothrow_copy_constructor
+ template<typename _Tp>
+ struct has_nothrow_copy_constructor
+ : public integral_constant<bool, __has_nothrow_copy(_Tp)>
+ { };
+
+ /// has_nothrow_assign
+ template<typename _Tp>
+ struct has_nothrow_assign
+ : public integral_constant<bool, __has_nothrow_assign(_Tp)>
+ { };
+
+ // Relationships between types.
+
+ /// is_base_of
+ template<typename _Base, typename _Derived>
+ struct is_base_of
+ : public integral_constant<bool, __is_base_of(_Base, _Derived)>
+ { };
+
+ template<typename _From, typename _To,
+ bool = (is_void<_From>::value || is_void<_To>::value
+ || is_function<_To>::value || is_array<_To>::value)>
+ struct __is_convertible_helper
+ { static const bool __value = (is_void<_From>::value
+ && is_void<_To>::value); };
+
+ template<typename _From, typename _To>
+ class __is_convertible_helper<_From, _To, false>
+ : public __sfinae_types
+ {
+ static __one __test(_To);
+ static __two __test(...);
+
+ public:
+ static const bool __value = sizeof(__test(declval<_From>())) == 1;
+ };
+
+ /// is_convertible
+ // XXX FIXME
+ // The C++0x specifications require front-end support, see N2255.
+ template<typename _From, typename _To>
+ struct is_convertible
+ : public integral_constant<bool,
+ __is_convertible_helper<_From, _To>::__value>
+ { };
+
+ /// is_explicitly_convertible
+ template<typename _From, typename _To>
+ struct is_explicitly_convertible
+ : public is_constructible<_To, _From>
+ { };
+
+ template<std::size_t _Len>
+ struct __aligned_storage_msa
+ {
+ union __type
+ {
+ unsigned char __data[_Len];
+ struct __attribute__((__aligned__)) { } __align;
+ };
+ };
+
+ /**
+ * @brief Alignment type.
+ *
+ * The value of _Align is a default-alignment which shall be the
+ * most stringent alignment requirement for any C++ object type
+ * whose size is no greater than _Len (3.9). The member typedef
+ * type shall be a POD type suitable for use as uninitialized
+ * storage for any object whose size is at most _Len and whose
+ * alignment is a divisor of _Align.
+ */
+ template<std::size_t _Len, std::size_t _Align =
+ __alignof__(typename __aligned_storage_msa<_Len>::__type)>
+ struct aligned_storage
+ {
+ union type
+ {
+ unsigned char __data[_Len];
+ struct __attribute__((__aligned__((_Align)))) { } __align;
+ };
+ };
+
+
+ // Define a nested type if some predicate holds.
+ // Primary template.
+ /// enable_if
+ template<bool, typename _Tp = void>
+ struct enable_if
+ { };
+
+ // Partial specialization for true.
+ template<typename _Tp>
+ struct enable_if<true, _Tp>
+ { typedef _Tp type; };
+
+
+ // A conditional expression, but for types. If true, first, if false, second.
+ // Primary template.
+ /// conditional
+ template<bool _Cond, typename _Iftrue, typename _Iffalse>
+ struct conditional
+ { typedef _Iftrue type; };
+
+ // Partial specialization for false.
+ template<typename _Iftrue, typename _Iffalse>
+ struct conditional<false, _Iftrue, _Iffalse>
+ { typedef _Iffalse type; };
+
+
+ // Decay trait for arrays and functions, used for perfect forwarding
+ // in make_pair, make_tuple, etc.
+ template<typename _Up,
+ bool _IsArray = is_array<_Up>::value,
+ bool _IsFunction = is_function<_Up>::value>
+ struct __decay_selector;
+
+ // NB: DR 705.
+ template<typename _Up>
+ struct __decay_selector<_Up, false, false>
+ { typedef typename remove_cv<_Up>::type __type; };
+
+ template<typename _Up>
+ struct __decay_selector<_Up, true, false>
+ { typedef typename remove_extent<_Up>::type* __type; };
+
+ template<typename _Up>
+ struct __decay_selector<_Up, false, true>
+ { typedef typename add_pointer<_Up>::type __type; };
+
+ /// decay
+ template<typename _Tp>
+ class decay
+ {
+ typedef typename remove_reference<_Tp>::type __remove_type;
+
+ public:
+ typedef typename __decay_selector<__remove_type>::__type type;
+ };
+
+
+ // Utility for constructing identically cv-qualified types.
+ template<typename _Unqualified, bool _IsConst, bool _IsVol>
+ struct __cv_selector;
+
+ template<typename _Unqualified>
+ struct __cv_selector<_Unqualified, false, false>
+ { typedef _Unqualified __type; };
+
+ template<typename _Unqualified>
+ struct __cv_selector<_Unqualified, false, true>
+ { typedef volatile _Unqualified __type; };
+
+ template<typename _Unqualified>
+ struct __cv_selector<_Unqualified, true, false>
+ { typedef const _Unqualified __type; };
+
+ template<typename _Unqualified>
+ struct __cv_selector<_Unqualified, true, true>
+ { typedef const volatile _Unqualified __type; };
+
+ template<typename _Qualified, typename _Unqualified,
+ bool _IsConst = is_const<_Qualified>::value,
+ bool _IsVol = is_volatile<_Qualified>::value>
+ class __match_cv_qualifiers
+ {
+ typedef __cv_selector<_Unqualified, _IsConst, _IsVol> __match;
+
+ public:
+ typedef typename __match::__type __type;
+ };
+
+
+ // Utility for finding the unsigned versions of signed integral types.
+ template<typename _Tp>
+ struct __make_unsigned
+ { typedef _Tp __type; };
+
+ template<>
+ struct __make_unsigned<char>
+ { typedef unsigned char __type; };
+
+ template<>
+ struct __make_unsigned<signed char>
+ { typedef unsigned char __type; };
+
+ template<>
+ struct __make_unsigned<short>
+ { typedef unsigned short __type; };
+
+ template<>
+ struct __make_unsigned<int>
+ { typedef unsigned int __type; };
+
+ template<>
+ struct __make_unsigned<long>
+ { typedef unsigned long __type; };
+
+ template<>
+ struct __make_unsigned<long long>
+ { typedef unsigned long long __type; };
+
+
+ // Select between integral and enum: not possible to be both.
+ template<typename _Tp,
+ bool _IsInt = is_integral<_Tp>::value,
+ bool _IsEnum = is_enum<_Tp>::value>
+ class __make_unsigned_selector;
+
+ template<typename _Tp>
+ class __make_unsigned_selector<_Tp, true, false>
+ {
+ typedef __make_unsigned<typename remove_cv<_Tp>::type> __unsignedt;
+ typedef typename __unsignedt::__type __unsigned_type;
+ typedef __match_cv_qualifiers<_Tp, __unsigned_type> __cv_unsigned;
+
+ public:
+ typedef typename __cv_unsigned::__type __type;
+ };
+
+ template<typename _Tp>
+ class __make_unsigned_selector<_Tp, false, true>
+ {
+ // With -fshort-enums, an enum may be as small as a char.
+ typedef unsigned char __smallest;
+ static const bool __b0 = sizeof(_Tp) <= sizeof(__smallest);
+ static const bool __b1 = sizeof(_Tp) <= sizeof(unsigned short);
+ static const bool __b2 = sizeof(_Tp) <= sizeof(unsigned int);
+ typedef conditional<__b2, unsigned int, unsigned long> __cond2;
+ typedef typename __cond2::type __cond2_type;
+ typedef conditional<__b1, unsigned short, __cond2_type> __cond1;
+ typedef typename __cond1::type __cond1_type;
+
+ public:
+ typedef typename conditional<__b0, __smallest, __cond1_type>::type __type;
+ };
+
+ // Given an integral/enum type, return the corresponding unsigned
+ // integer type.
+ // Primary template.
+ /// make_unsigned
+ template<typename _Tp>
+ struct make_unsigned
+ { typedef typename __make_unsigned_selector<_Tp>::__type type; };
+
+ // Integral, but don't define.
+ template<>
+ struct make_unsigned<bool>;
+
+
+ // Utility for finding the signed versions of unsigned integral types.
+ template<typename _Tp>
+ struct __make_signed
+ { typedef _Tp __type; };
+
+ template<>
+ struct __make_signed<char>
+ { typedef signed char __type; };
+
+ template<>
+ struct __make_signed<unsigned char>
+ { typedef signed char __type; };
+
+ template<>
+ struct __make_signed<unsigned short>
+ { typedef signed short __type; };
+
+ template<>
+ struct __make_signed<unsigned int>
+ { typedef signed int __type; };
+
+ template<>
+ struct __make_signed<unsigned long>
+ { typedef signed long __type; };
+
+ template<>
+ struct __make_signed<unsigned long long>
+ { typedef signed long long __type; };
+
+
+ // Select between integral and enum: not possible to be both.
+ template<typename _Tp,
+ bool _IsInt = is_integral<_Tp>::value,
+ bool _IsEnum = is_enum<_Tp>::value>
+ class __make_signed_selector;
+
+ template<typename _Tp>
+ class __make_signed_selector<_Tp, true, false>
+ {
+ typedef __make_signed<typename remove_cv<_Tp>::type> __signedt;
+ typedef typename __signedt::__type __signed_type;
+ typedef __match_cv_qualifiers<_Tp, __signed_type> __cv_signed;
+
+ public:
+ typedef typename __cv_signed::__type __type;
+ };
+
+ template<typename _Tp>
+ class __make_signed_selector<_Tp, false, true>
+ {
+ // With -fshort-enums, an enum may be as small as a char.
+ typedef signed char __smallest;
+ static const bool __b0 = sizeof(_Tp) <= sizeof(__smallest);
+ static const bool __b1 = sizeof(_Tp) <= sizeof(signed short);
+ static const bool __b2 = sizeof(_Tp) <= sizeof(signed int);
+ typedef conditional<__b2, signed int, signed long> __cond2;
+ typedef typename __cond2::type __cond2_type;
+ typedef conditional<__b1, signed short, __cond2_type> __cond1;
+ typedef typename __cond1::type __cond1_type;
+
+ public:
+ typedef typename conditional<__b0, __smallest, __cond1_type>::type __type;
+ };
+
+ // Given an integral/enum type, return the corresponding signed
+ // integer type.
+ // Primary template.
+ /// make_signed
+ template<typename _Tp>
+ struct make_signed
+ { typedef typename __make_signed_selector<_Tp>::__type type; };
+
+ // Integral, but don't define.
+ template<>
+ struct make_signed<bool>;
+
+ /// common_type
+ template<typename... _Tp>
+ struct common_type;
+
+ template<typename _Tp>
+ struct common_type<_Tp>
+ { typedef _Tp type; };
+
+ template<typename _Tp, typename _Up>
+ struct common_type<_Tp, _Up>
+ { typedef decltype(true ? declval<_Tp>() : declval<_Up>()) type; };
+
+ template<typename _Tp, typename _Up, typename... _Vp>
+ struct common_type<_Tp, _Up, _Vp...>
+ {
+ typedef typename
+ common_type<typename common_type<_Tp, _Up>::type, _Vp...>::type type;
+ };
+ // @} group metaprogramming
+
+ /// declval
+ template<typename _Tp>
+ struct __declval_protector
+ {
+ static const bool __stop = false;
+ static typename add_rvalue_reference<_Tp>::type __delegate();
+ };
+
+ template<typename _Tp>
+ inline typename add_rvalue_reference<_Tp>::type
+ declval()
+ {
+ static_assert(__declval_protector<_Tp>::__stop,
+ "declval() must not be used!");
+ return __declval_protector<_Tp>::__delegate();
+ }
+}
+
+#endif // __GXX_EXPERIMENTAL_CXX0X__
+
+#endif // _GLIBCXX_TYPE_TRAITS
diff --git a/aos/externals/WPILib/Makefile b/aos/externals/WPILib/Makefile
new file mode 100644
index 0000000..6e13be8
--- /dev/null
+++ b/aos/externals/WPILib/Makefile
@@ -0,0 +1,25 @@
+all: make.rb WPILib.a
+ #ruby make.rb
+clean:
+ rm -f *.out WPILib/*.o WPILib/*/*.o *.d
+
+deploy: all
+ ncftpput robot /ni-rt/system/ wpilib.out
+
+wpilibupdate.exe:
+ wget http://firstforge.wpi.edu/sf/frs/do/downloadFile/projects.wpilib/frs.2012_update_for_c.frc_update_3111/frs1405?dl=1 -O wpilibupdate.exe
+
+WPILib: wpilibupdate.exe
+ mkdir wpilibinstaller
+ cd wpilibinstaller
+ unzip wpilibupdate.exe -d wpilibinstaller/ | tee wpilibinstaller/unziplog.txt
+ cat wpilibinstaller/unziplog.txt | grep "inflating: wpilibinstaller/.*\.zip" | sed "s/.*\(wpilibinstaller\/.*\.zip\).*/\1/" | xargs -I '{}' cp '{}' ./
+ #cat wpilibinstaller/unziplog.txt | grep "inflating: wpilibinstaller/.*\.zip" | sed "s/.*wpilibinstaller\/\(.*\.zip\).*/\1/" | xargs -I '{}' ln -s '{}' ./WPILib.zip
+ unzip -a WPILib*.zip
+ rm -r wpilibinstaller
+ rm -f wpilib_page1.url wpilib_page2.url wpilib_page3.url
+
+WPILib.a: wpilibupdate.exe
+ unzip wpilibupdate.exe
+ cp vxworks-6.3/target/lib/WPILib.a ./
+
diff --git a/aos/externals/WPILib/WPILib.a b/aos/externals/WPILib/WPILib.a
new file mode 100644
index 0000000..278a2a2
--- /dev/null
+++ b/aos/externals/WPILib/WPILib.a
Binary files differ
diff --git a/aos/externals/WPILib/WPILib/.cproject b/aos/externals/WPILib/WPILib/.cproject
new file mode 100644
index 0000000..dc5fad2
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/.cproject
@@ -0,0 +1,31 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<?fileVersion 4.0.0?>
+
+<cproject>
+<storageModule moduleId="org.eclipse.cdt.core.settings">
+<cconfiguration id="org.eclipse.cdt.core.default.config.1075613688">
+<storageModule buildSystemId="org.eclipse.cdt.core.defaultConfigDataProvider" id="org.eclipse.cdt.core.default.config.1075613688" moduleId="org.eclipse.cdt.core.settings" name="Configuration">
+<externalSettings/>
+<extensions>
+<extension id="com.windriver.ide.core.WRScannerInfoProvider" point="org.eclipse.cdt.core.ScannerInfoProvider"/>
+<extension id="com.windriver.ide.core.WRElfParserVxWorks" point="org.eclipse.cdt.core.BinaryParser"/>
+<extension id="org.eclipse.cdt.core.GNU_ELF" point="org.eclipse.cdt.core.BinaryParser"/>
+</extensions>
+</storageModule>
+<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
+
+<storageModule moduleId="scannerConfiguration"/>
+<storageModule moduleId="userdefinedContainer">
+<indexAllFiles value="false"/>
+<initialized value="true"/>
+</storageModule>
+<storageModule moduleId="org.eclipse.cdt.core.language.mapping"/>
+<storageModule moduleId="org.eclipse.cdt.core.pathentry">
+<pathentry excluding="PPC603gnu/|.svn/|.settings/" kind="src" path=""/>
+<pathentry kind="out" path=""/>
+<pathentry kind="con" path="com.windriver.ide.core.WR_CONTAINER"/>
+<pathentry kind="con" path="com.windriver.ide.core.build.model.WR_USERDEFINED_CONTAINER"/>
+</storageModule>
+</cconfiguration>
+</storageModule>
+</cproject>
diff --git a/aos/externals/WPILib/WPILib/.project b/aos/externals/WPILib/WPILib/.project
new file mode 100644
index 0000000..f2fb2cc
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/.project
@@ -0,0 +1,20 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<projectDescription>
+ <name>WPILib</name>
+ <comment></comment>
+ <projects>
+ </projects>
+ <buildSpec>
+ <buildCommand>
+ <name>com.windriver.ide.core.wrbuilder</name>
+ <arguments>
+ </arguments>
+ </buildCommand>
+ </buildSpec>
+ <natures>
+ <nature>com.windriver.ide.core.wrnature</nature>
+ <nature>com.windriver.ide.core.wrcorenature</nature>
+ <nature>org.eclipse.cdt.core.cnature</nature>
+ <nature>org.eclipse.cdt.core.ccnature</nature>
+ </natures>
+</projectDescription>
diff --git a/aos/externals/WPILib/WPILib/.settings/Makefile b/aos/externals/WPILib/WPILib/.settings/Makefile
new file mode 100644
index 0000000..bc19164
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/.settings/Makefile
@@ -0,0 +1,2184 @@
+# Wind River Workbench generated Makefile.
+# Do not edit!!!
+#
+# The file ".wrmakefile" is the template used by the Wind River Workbench to
+# generate the makefiles of this project. Add user-specific build targets and
+# make rules only(!) in this project's ".wrmakefile" file. These will then be
+# automatically dumped into the makefiles.
+
+WIND_HOME := $(subst \,/,$(WIND_HOME))
+WIND_BASE := $(subst \,/,$(WIND_BASE))
+WIND_USR := $(subst \,/,$(WIND_USR))
+
+all : pre_build main_all post_build
+
+_clean ::
+ @echo "make: removing targets and objects of `pwd`"
+
+TRACE=0
+TRACEON=$(TRACE:0=@)
+TRACE_FLAG=$(TRACEON:1=)
+
+MAKEFILE := Makefile
+
+BUILD_SPEC = PPC603gnu
+DEBUG_MODE = 1
+SRC_DIR := .
+BUILD_ROOT_DIR :=
+PRJ_ROOT_DIR := C:/windriver/workspace/WPILib
+WS_ROOT_DIR := C:/windriver/workspace
+
+ALL_BUILD_SPECS := PPC32diab PPC32gnu PPC32sfdiab PPC32sfgnu \
+ PPC403diab PPC403gnu PPC405diab PPC405gnu \
+ PPC405sfdiab PPC405sfgnu PPC440diab PPC440gnu \
+ PPC440sfdiab PPC440sfgnu PPC603diab PPC603gnu \
+ PPC604diab PPC604gnu PPC85XXdiab PPC85XXgnu \
+ PPC85XXsfdiab PPC85XXsfgnu PPC860sfdiab PPC860sfgnu \
+ SIMLINUXdiab SIMLINUXgnu SIMNTdiab SIMNTgnu \
+ SIMSPARCSOLARISdiab SIMSPARCSOLARISgnu
+ENABLED_BUILD_SPECS := PPC603gnu
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32diab_DEBUG
+else
+OBJ_DIR := PPC32diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32gnu_DEBUG
+else
+OBJ_DIR := PPC32gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfdiab_DEBUG
+else
+OBJ_DIR := PPC32sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfgnu_DEBUG
+else
+OBJ_DIR := PPC32sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403diab_DEBUG
+else
+OBJ_DIR := PPC403diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403gnu_DEBUG
+else
+OBJ_DIR := PPC403gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405diab_DEBUG
+else
+OBJ_DIR := PPC405diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405gnu_DEBUG
+else
+OBJ_DIR := PPC405gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfdiab_DEBUG
+else
+OBJ_DIR := PPC405sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfgnu_DEBUG
+else
+OBJ_DIR := PPC405sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440diab_DEBUG
+else
+OBJ_DIR := PPC440diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440gnu_DEBUG
+else
+OBJ_DIR := PPC440gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfdiab_DEBUG
+else
+OBJ_DIR := PPC440sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfgnu_DEBUG
+else
+OBJ_DIR := PPC440sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603diab_DEBUG
+else
+OBJ_DIR := PPC603diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603gnu_DEBUG
+else
+OBJ_DIR := PPC603gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604diab_DEBUG
+else
+OBJ_DIR := PPC604diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604gnu_DEBUG
+else
+OBJ_DIR := PPC604gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXdiab_DEBUG
+else
+OBJ_DIR := PPC85XXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXgnu_DEBUG
+else
+OBJ_DIR := PPC85XXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfdiab_DEBUG
+else
+OBJ_DIR := PPC85XXsfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfgnu_DEBUG
+else
+OBJ_DIR := PPC85XXsfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfdiab_DEBUG
+else
+OBJ_DIR := PPC860sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfgnu_DEBUG
+else
+OBJ_DIR := PPC860sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXdiab_DEBUG
+else
+OBJ_DIR := SIMLINUXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXgnu_DEBUG
+else
+OBJ_DIR := SIMLINUXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTdiab_DEBUG
+else
+OBJ_DIR := SIMNTdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTgnu_DEBUG
+else
+OBJ_DIR := SIMNTgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISdiab_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISgnu_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISgnu
+endif
+endif
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+
+PROJECT_TYPE = DKM
+DEFINES =
+EXPAND_DBG = 0
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFH:vxworks63 -Xstmw-slow -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mhard-float -mstrict-align -mno-implicit-fp -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -msoft-float -mstrict-align
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC403FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=403 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC603FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=603 -mstrict-align -mno-implicit-fp -mlongcall
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I.. -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC604FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=604 -mstrict-align -mno-implicit-fp
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC860FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=860 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tSPARCFH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC =
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+
+
+
+
+
+-include $(PRJ_ROOT_DIR)/*.makefile
+
+-include *.makefile
+
+main_all : external_build $(PROJECT_TARGETS)
+ @echo "make: built targets of `pwd`"
+
+# entry point for extending the build
+external_build ::
+ @echo ""
+
+# main entry point for pre processing prior to the build
+pre_build :: $(PRE_BUILD_STEP) generate_sources
+ @echo ""
+
+# entry point for generating sources prior to the build
+generate_sources ::
+ @echo ""
+
+# main entry point for post processing after the build
+post_build :: $(POST_BUILD_STEP) deploy_output
+ @echo ""
+
+# entry point for deploying output after the build
+deploy_output ::
+ @echo ""
+
+clean :: external_clean $(CLEAN_STEP) _clean
+
+# entry point for extending the build clean
+external_clean ::
+ @echo ""
diff --git a/aos/externals/WPILib/WPILib/.settings/org.eclipse.ltk.core.refactoring.prefs b/aos/externals/WPILib/WPILib/.settings/org.eclipse.ltk.core.refactoring.prefs
new file mode 100644
index 0000000..efc568c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/.settings/org.eclipse.ltk.core.refactoring.prefs
@@ -0,0 +1,3 @@
+#Tue Sep 14 17:17:39 EDT 2010
+eclipse.preferences.version=1
+org.eclipse.ltk.core.refactoring.enable.project.refactoring.history=false
diff --git a/aos/externals/WPILib/WPILib/.wrmakefile b/aos/externals/WPILib/WPILib/.wrmakefile
new file mode 100644
index 0000000..6ad1e05
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/.wrmakefile
@@ -0,0 +1,48 @@
+# The file ".wrmakefile" is the template used by the Wind River Workbench to
+# generate the makefiles of this project. Add user-specific build targets and
+# make rules only(!) in this project's ".wrmakefile" file. These will then be
+# automatically dumped into the makefiles.
+
+WIND_HOME := $(subst \,/,$(WIND_HOME))
+WIND_BASE := $(subst \,/,$(WIND_BASE))
+WIND_USR := $(subst \,/,$(WIND_USR))
+
+all : pre_build main_all post_build
+
+_clean ::
+ @echo "make: removing targets and objects of `pwd`"
+
+%IDE_GENERATED%
+
+-include $(PRJ_ROOT_DIR)/*.makefile
+
+-include *.makefile
+
+main_all : external_build $(PROJECT_TARGETS)
+ @echo "make: built targets of `pwd`"
+
+# entry point for extending the build
+external_build ::
+ @echo ""
+
+# main entry point for pre processing prior to the build
+pre_build :: $(PRE_BUILD_STEP) generate_sources
+ @echo ""
+
+# entry point for generating sources prior to the build
+generate_sources ::
+ @echo ""
+
+# main entry point for post processing after the build
+post_build :: $(POST_BUILD_STEP) deploy_output
+ @echo ""
+
+# entry point for deploying output after the build
+deploy_output ::
+ @echo ""
+
+clean :: external_clean $(CLEAN_STEP) _clean
+
+# entry point for extending the build clean
+external_clean ::
+ @echo ""
diff --git a/aos/externals/WPILib/WPILib/.wrproject b/aos/externals/WPILib/WPILib/.wrproject
new file mode 100644
index 0000000..d55d2e9
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/.wrproject
@@ -0,0 +1,1414 @@
+<?xml version="1.0" encoding="UTF-8" standalone="no"?>
+<wrxml>
+ <properties platform="VxWorks" platform_name="vxworks-6.3" root="0" type="DownloadableKernelModuleProject"/>
+ <attributes>
+ <mapAttribute>
+ <listAttribute key="BLD::Info|GlobalMacros">
+ <stringAttribute value="PROJECT_TYPE"/>
+ <stringAttribute value="DEFINES"/>
+ <stringAttribute value="EXPAND_DBG"/>
+ </listAttribute>
+ <stringAttribute key="BLD::Info|GlobalMacro|DEFINES" value=""/>
+ <stringAttribute key="BLD::Info|GlobalMacro|EXPAND_DBG" value="0"/>
+ <stringAttribute key="BLD::Info|GlobalMacro|PROJECT_TYPE" value="DKM"/>
+ <listAttribute key="BLD::Info|Incl|PPC32diab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC32gnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC32sfdiab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC32sfgnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC403diab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC403gnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC405diab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC405gnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC405sfdiab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC405sfgnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC440diab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC440gnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC440sfdiab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC440sfgnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC603diab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC603gnu">
+ <stringAttribute value="-I.."/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC604diab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC604gnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC85XXdiab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC85XXgnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC85XXsfdiab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC85XXsfgnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC860sfdiab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|PPC860sfgnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|SIMLINUXdiab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|SIMLINUXgnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|SIMNTdiab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|SIMNTgnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|SIMSPARCSOLARISdiab">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Incl|SIMSPARCSOLARISgnu">
+ <stringAttribute value="-I$(WIND_BASE)/target/h"/>
+ <stringAttribute value="-I$(WIND_BASE)/target/h/wrn/coreip"/>
+ </listAttribute>
+ <listAttribute key="BLD::Info|Macros">
+ <stringAttribute value="VX_CPU_FAMILY"/>
+ <stringAttribute value="CPU"/>
+ <stringAttribute value="TOOL_FAMILY"/>
+ <stringAttribute value="TOOL"/>
+ <stringAttribute value="TOOL_PATH"/>
+ <stringAttribute value="CC_ARCH_SPEC"/>
+ <stringAttribute value="LIBPATH"/>
+ <stringAttribute value="LIBS"/>
+ </listAttribute>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC32diab" value="-tPPCFH:vxworks63 -Xstmw-slow -DPPC32_fp60x"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC32gnu" value="-mhard-float -mstrict-align -mno-implicit-fp -DPPC32_fp60x"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC32sfdiab" value="-tPPCFS:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC32sfgnu" value="-msoft-float -mstrict-align"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC403diab" value="-tPPC403FS:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC403gnu" value="-mcpu=403 -mstrict-align -msoft-float"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC405diab" value="-tPPC405FS:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC405gnu" value="-mcpu=405 -mstrict-align -msoft-float"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC405sfdiab" value="-tPPC405FS:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC405sfgnu" value="-mcpu=405 -mstrict-align -msoft-float"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC440diab" value="-tPPC440FH:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC440gnu" value="-mcpu=440 -mstrict-align -msoft-float"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC440sfdiab" value="-tPPC440FS:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC440sfgnu" value="-mcpu=440 -mstrict-align -msoft-float"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC603diab" value="-tPPC603FH:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC603gnu" value="-mcpu=603 -mstrict-align -mno-implicit-fp -mlongcall"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC604diab" value="-tPPC604FH:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC604gnu" value="-mcpu=604 -mstrict-align -mno-implicit-fp"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC85XXdiab" value="-tPPCE500FS:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC85XXgnu" value="-mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC85XXsfdiab" value="-tPPCE500FS:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC85XXsfgnu" value="-mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC860sfdiab" value="-tPPC860FS:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|PPC860sfgnu" value="-mcpu=860 -mstrict-align -msoft-float"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|SIMLINUXdiab" value="-tX86LH:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|SIMLINUXgnu" value="-mtune=i486 -march=i486"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|SIMNTdiab" value="-tX86LH:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|SIMNTgnu" value="-mtune=i486 -march=i486"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|SIMSPARCSOLARISdiab" value="-tSPARCFH:vxworks63"/>
+ <stringAttribute key="BLD::Info|Macro|CC_ARCH_SPEC|value|SIMSPARCSOLARISgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC32diab" value="PPC32"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC32gnu" value="PPC32"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC32sfdiab" value="PPC32"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC32sfgnu" value="PPC32"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC403diab" value="PPC403"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC403gnu" value="PPC403"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC405diab" value="PPC405"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC405gnu" value="PPC405"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC405sfdiab" value="PPC405"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC405sfgnu" value="PPC405"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC440diab" value="PPC440"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC440gnu" value="PPC440"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC440sfdiab" value="PPC440"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC440sfgnu" value="PPC440"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC603diab" value="PPC603"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC603gnu" value="PPC603"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC604diab" value="PPC604"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC604gnu" value="PPC604"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC85XXdiab" value="PPC85XX"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC85XXgnu" value="PPC85XX"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC85XXsfdiab" value="PPC85XX"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC85XXsfgnu" value="PPC85XX"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC860sfdiab" value="PPC860"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|PPC860sfgnu" value="PPC860"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|SIMLINUXdiab" value="SIMLINUX"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|SIMLINUXgnu" value="SIMLINUX"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|SIMNTdiab" value="SIMNT"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|SIMNTgnu" value="SIMNT"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|SIMSPARCSOLARISdiab" value="SIMSPARCSOLARIS"/>
+ <stringAttribute key="BLD::Info|Macro|CPU|value|SIMSPARCSOLARISgnu" value="SIMSPARCSOLARIS"/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC32diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC32gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC32sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC32sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC403diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC403gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC405diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC405gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC405sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC405sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC440diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC440gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC440sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC440sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC603diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC603gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC604diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC604gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC85XXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC85XXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC85XXsfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC85XXsfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC860sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|PPC860sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|SIMLINUXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|SIMLINUXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|SIMNTdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|SIMNTgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|SIMSPARCSOLARISdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBPATH|value|SIMSPARCSOLARISgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC32diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC32gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC32sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC32sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC403diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC403gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC405diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC405gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC405sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC405sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC440diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC440gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC440sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC440sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC603diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC603gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC604diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC604gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC85XXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC85XXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC85XXsfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC85XXsfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC860sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|PPC860sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|SIMLINUXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|SIMLINUXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|SIMNTdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|SIMNTgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|SIMSPARCSOLARISdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|LIBS|value|SIMSPARCSOLARISgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC32diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC32gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC32sfdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC32sfgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC403diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC403gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC405diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC405gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC405sfdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC405sfgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC440diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC440gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC440sfdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC440sfgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC603diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC603gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC604diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC604gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC85XXdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC85XXgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC85XXsfdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC85XXsfgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC860sfdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|PPC860sfgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|SIMLINUXdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|SIMLINUXgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|SIMNTdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|SIMNTgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|SIMSPARCSOLARISdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_FAMILY|value|SIMSPARCSOLARISgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC32diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC32gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC32sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC32sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC403diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC403gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC405diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC405gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC405sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC405sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC440diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC440gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC440sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC440sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC603diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC603gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC604diab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC604gnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC85XXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC85XXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC85XXsfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC85XXsfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC860sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|PPC860sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|SIMLINUXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|SIMLINUXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|SIMNTdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|SIMNTgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|SIMSPARCSOLARISdiab" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL_PATH|value|SIMSPARCSOLARISgnu" value=""/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC32diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC32gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC32sfdiab" value="sfdiab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC32sfgnu" value="sfgnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC403diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC403gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC405diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC405gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC405sfdiab" value="sfdiab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC405sfgnu" value="sfgnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC440diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC440gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC440sfdiab" value="sfdiab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC440sfgnu" value="sfgnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC603diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC603gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC604diab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC604gnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC85XXdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC85XXgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC85XXsfdiab" value="sfdiab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC85XXsfgnu" value="sfgnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC860sfdiab" value="sfdiab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|PPC860sfgnu" value="sfgnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|SIMLINUXdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|SIMLINUXgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|SIMNTdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|SIMNTgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|SIMSPARCSOLARISdiab" value="diab"/>
+ <stringAttribute key="BLD::Info|Macro|TOOL|value|SIMSPARCSOLARISgnu" value="gnu"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC32diab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC32gnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC32sfdiab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC32sfgnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC403diab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC403gnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC405diab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC405gnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC405sfdiab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC405sfgnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC440diab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC440gnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC440sfdiab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC440sfgnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC603diab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC603gnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC604diab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC604gnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC85XXdiab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC85XXgnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC85XXsfdiab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC85XXsfgnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC860sfdiab" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|PPC860sfgnu" value="ppc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|SIMLINUXdiab" value="simlinux"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|SIMLINUXgnu" value="simlinux"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|SIMNTdiab" value="simpc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|SIMNTgnu" value="simpc"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|SIMSPARCSOLARISdiab" value="simso"/>
+ <stringAttribute key="BLD::Info|Macro|VX_CPU_FAMILY|value|SIMSPARCSOLARISgnu" value="simso"/>
+ <listAttribute key="BLD::Info|Tools">
+ <stringAttribute value="C-Compiler"/>
+ <stringAttribute value="C++-Compiler"/>
+ <stringAttribute value="Linker"/>
+ <stringAttribute value="Partial Image Linker"/>
+ <stringAttribute value="Librarian"/>
+ <stringAttribute value="Assembler"/>
+ </listAttribute>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC32diab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC32gnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC32sfdiab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC32sfgnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC403diab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC403gnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC405diab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC405gnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC405sfdiab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC405sfgnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC440diab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC440gnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC440sfdiab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC440sfgnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC603diab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC603gnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC604diab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC604gnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC85XXdiab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC85XXgnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC85XXsfdiab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC85XXsfgnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC860sfdiab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|PPC860sfgnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|SIMLINUXdiab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|SIMLINUXgnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccpentium %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|SIMNTdiab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|SIMNTgnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccpentium %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|SIMSPARCSOLARISdiab" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|cmd|SIMSPARCSOLARISgnu" value="echo "building $@";%assemblerprefix% $(TOOL_PATH)ccsparc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC32diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC32gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC32sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC32sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC403diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC403gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC405diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC405gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC405sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC405sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC440diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC440gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC440sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC440sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC603diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC603gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC604diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC604gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC85XXdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC85XXgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC85XXsfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC85XXsfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC860sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|PPC860sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|SIMLINUXdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|SIMLINUXgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|SIMNTdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|SIMNTgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|SIMSPARCSOLARISdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|dbgFlags|SIMSPARCSOLARISgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC32diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC32gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC32sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC32sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC403diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC403gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC405diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC405gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC405sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC405sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC440diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC440gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC440sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC440sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC603diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC603gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC604diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC604gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC85XXdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC85XXgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC85XXsfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC85XXsfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC860sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|PPC860sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|SIMLINUXdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|SIMLINUXgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|SIMNTdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|SIMNTgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|SIMSPARCSOLARISdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|derivedSigs|SIMSPARCSOLARISgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC32diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC32gnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC32sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC32sfgnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC403diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC403gnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC405diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC405gnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC405sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC405sfgnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC440diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC440gnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC440sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC440sfgnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC603diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC603gnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC604diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC604gnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC85XXdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC85XXgnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC85XXsfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC85XXsfgnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC860sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|PPC860sfgnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|SIMLINUXdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|SIMLINUXgnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|SIMNTdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|SIMNTgnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|SIMSPARCSOLARISdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|flags|SIMSPARCSOLARISgnu" value="$(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC32diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC32gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC32sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC32sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC403diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC403gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC405diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC405gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC405sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC405sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC440diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC440gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC440sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC440sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC603diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC603gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC604diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC604gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC85XXdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC85XXgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC85XXsfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC85XXsfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC860sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|PPC860sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|SIMLINUXdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|SIMLINUXgnu" value="-O2 -nostdlib -fno-builtin -fno-defer-pop"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|SIMNTdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|SIMNTgnu" value="-O2 -nostdlib -fno-builtin -fno-defer-pop"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|SIMSPARCSOLARISdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|nonDbgFlags|SIMSPARCSOLARISgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <booleanAttribute key="BLD::Info|Tool|Assembler|object" value="true"/>
+ <booleanAttribute key="BLD::Info|Tool|Assembler|passAble" value="false"/>
+ <stringAttribute key="BLD::Info|Tool|Assembler|sigs" value="*.s"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC32diab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC32gnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC32sfdiab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC32sfgnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC403diab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC403gnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC405diab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC405gnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC405sfdiab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC405sfgnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC440diab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC440gnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC440sfdiab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC440sfgnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC603diab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC603gnu" value="%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC604diab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC604gnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC85XXdiab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC85XXgnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC85XXsfdiab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC85XXsfgnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC860sfdiab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC860sfgnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|SIMLINUXdiab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|SIMLINUXgnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccpentium %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|SIMNTdiab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|SIMNTgnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccpentium %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|SIMSPARCSOLARISdiab" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|SIMSPARCSOLARISgnu" value="echo "building $@";%cppcompilerprefix% $(TOOL_PATH)ccsparc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC32diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC32gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC32sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC32sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC403diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC403gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC405diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC405gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC405sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC405sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC440diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC440gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC440sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC440sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC603diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC603gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC604diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC604gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC85XXdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC85XXgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC85XXsfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC85XXsfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC860sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|PPC860sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|SIMLINUXdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|SIMLINUXgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|SIMNTdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|SIMNTgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|SIMSPARCSOLARISdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|dbgFlags|SIMSPARCSOLARISgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC32diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC32gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC32sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC32sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC403diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC403gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC405diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC405gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC405sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC405sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC440diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC440gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC440sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC440sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC603diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC603gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC604diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC604gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC85XXdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC85XXgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC85XXsfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC85XXsfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC860sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|PPC860sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|SIMLINUXdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|SIMLINUXgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|SIMNTdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|SIMNTgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|SIMSPARCSOLARISdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|derivedSigs|SIMSPARCSOLARISgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC32diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC32gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC32sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC32sfgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC403diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC403gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC405diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC405gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC405sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC405sfgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC440diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC440gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC440sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC440sfgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC603diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC603gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC604diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC604gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC85XXdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC85XXgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC85XXsfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC85XXsfgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC860sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|PPC860sfgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|SIMLINUXdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|SIMLINUXgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|SIMNTdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|SIMNTgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|SIMSPARCSOLARISdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|flags|SIMSPARCSOLARISgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC32diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC32gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC32sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC32sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC403diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC403gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC405diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC405gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC405sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC405sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC440diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC440gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC440sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC440sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC603diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC603gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC604diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC604gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC85XXdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC85XXgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC85XXsfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC85XXsfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC860sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|PPC860sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|SIMLINUXdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|SIMLINUXgnu" value="-O2 -nostdlib -fno-builtin -fno-defer-pop"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|SIMNTdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|SIMNTgnu" value="-O2 -nostdlib -fno-builtin -fno-defer-pop"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|SIMSPARCSOLARISdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|nonDbgFlags|SIMSPARCSOLARISgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <booleanAttribute key="BLD::Info|Tool|C++-Compiler|object" value="true"/>
+ <booleanAttribute key="BLD::Info|Tool|C++-Compiler|passAble" value="false"/>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|sigs" value="*.cpp;*.C;*.cxx;*.cc"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC32diab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC32gnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC32sfdiab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC32sfgnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC403diab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC403gnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC405diab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC405gnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC405sfdiab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC405sfgnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC440diab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC440gnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC440sfdiab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC440sfgnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC603diab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC603gnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC604diab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC604gnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC85XXdiab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC85XXgnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC85XXsfdiab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC85XXsfgnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC860sfdiab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC860sfgnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|SIMLINUXdiab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|SIMLINUXgnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccpentium %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|SIMNTdiab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|SIMNTgnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccpentium %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|SIMSPARCSOLARISdiab" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|SIMSPARCSOLARISgnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccsparc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC32diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC32gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC32sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC32sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC403diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC403gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC405diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC405gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC405sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC405sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC440diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC440gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC440sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC440sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC603diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC603gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC604diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC604gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC85XXdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC85XXgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC85XXsfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC85XXsfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC860sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|PPC860sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|SIMLINUXdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|SIMLINUXgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|SIMNTdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|SIMNTgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|SIMSPARCSOLARISdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|dbgFlags|SIMSPARCSOLARISgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC32diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC32gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC32sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC32sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC403diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC403gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC405diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC405gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC405sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC405sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC440diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC440gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC440sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC440sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC603diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC603gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC604diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC604gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC85XXdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC85XXgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC85XXsfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC85XXsfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC860sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|PPC860sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|SIMLINUXdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|SIMLINUXgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|SIMNTdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|SIMNTgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|SIMSPARCSOLARISdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|derivedSigs|SIMSPARCSOLARISgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC32diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC32gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC32sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC32sfgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC403diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC403gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC405diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC405gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC405sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC405sfgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC440diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC440gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC440sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC440sfgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC603diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC603gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC604diab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC604gnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC85XXdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC85XXgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC85XXsfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC85XXsfgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC860sfdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|PPC860sfgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|SIMLINUXdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|SIMLINUXgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|SIMNTdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|SIMNTgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|SIMSPARCSOLARISdiab" value="$(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|flags|SIMSPARCSOLARISgnu" value="$(CC_ARCH_SPEC) -ansi -Wall -MD -MP"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC32diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC32gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC32sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC32sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC403diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC403gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC405diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC405gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC405sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC405sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC440diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC440gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC440sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC440sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC603diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC603gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC604diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC604gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC85XXdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC85XXgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC85XXsfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC85XXsfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC860sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|PPC860sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|SIMLINUXdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|SIMLINUXgnu" value="-O2 -nostdlib -fno-builtin -fno-defer-pop"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|SIMNTdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|SIMNTgnu" value="-O2 -nostdlib -fno-builtin -fno-defer-pop"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|SIMSPARCSOLARISdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|nonDbgFlags|SIMSPARCSOLARISgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <booleanAttribute key="BLD::Info|Tool|C-Compiler|object" value="true"/>
+ <booleanAttribute key="BLD::Info|Tool|C-Compiler|passAble" value="false"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|sigs" value="*.c"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC32diab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC32gnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC32sfdiab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC32sfgnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC403diab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC403gnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC405diab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC405gnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC405sfdiab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC405sfgnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC440diab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC440gnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC440sfdiab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC440sfgnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC603diab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC603gnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC604diab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC604gnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC85XXdiab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC85XXgnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC85XXsfdiab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC85XXsfgnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC860sfdiab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|PPC860sfgnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arppc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|SIMLINUXdiab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|SIMLINUXgnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arpentium %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|SIMNTdiab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|SIMNTgnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arpentium %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|SIMSPARCSOLARISdiab" value="echo "building $@";%archiverprefix% $(TOOL_PATH)dar %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|cmd|SIMSPARCSOLARISgnu" value="echo "building $@";%archiverprefix% $(TOOL_PATH)arsparc %ToolFlags% %OutFile% %Objects%"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC32diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC32gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC32sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC32sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC403diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC403gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC405diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC405gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC405sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC405sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC440diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC440gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC440sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC440sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC603diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC603gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC604diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC604gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC85XXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC85XXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC85XXsfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC85XXsfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC860sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|PPC860sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|SIMLINUXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|SIMLINUXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|SIMNTdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|SIMNTgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|SIMSPARCSOLARISdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|dbgFlags|SIMSPARCSOLARISgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC32diab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC32gnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC32sfdiab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC32sfgnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC403diab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC403gnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC405diab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC405gnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC405sfdiab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC405sfgnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC440diab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC440gnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC440sfdiab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC440sfgnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC603diab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC603gnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC604diab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC604gnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC85XXdiab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC85XXgnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC85XXsfdiab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC85XXsfgnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC860sfdiab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|PPC860sfgnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|SIMLINUXdiab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|SIMLINUXgnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|SIMNTdiab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|SIMNTgnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|SIMSPARCSOLARISdiab" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|derivedSigs|SIMSPARCSOLARISgnu" value="*.a"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC32diab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC32gnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC32sfdiab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC32sfgnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC403diab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC403gnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC405diab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC405gnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC405sfdiab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC405sfgnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC440diab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC440gnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC440sfdiab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC440sfgnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC603diab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC603gnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC604diab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC604gnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC85XXdiab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC85XXgnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC85XXsfdiab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC85XXsfgnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC860sfdiab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|PPC860sfgnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|SIMLINUXdiab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|SIMLINUXgnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|SIMNTdiab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|SIMNTgnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|SIMSPARCSOLARISdiab" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|flags|SIMSPARCSOLARISgnu" value="crus"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC32diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC32gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC32sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC32sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC403diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC403gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC405diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC405gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC405sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC405sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC440diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC440gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC440sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC440sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC603diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC603gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC604diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC604gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC85XXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC85XXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC85XXsfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC85XXsfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC860sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|PPC860sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|SIMLINUXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|SIMLINUXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|SIMNTdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|SIMNTgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|SIMSPARCSOLARISdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|nonDbgFlags|SIMSPARCSOLARISgnu" value=""/>
+ <booleanAttribute key="BLD::Info|Tool|Librarian|object" value="false"/>
+ <booleanAttribute key="BLD::Info|Tool|Librarian|passAble" value="true"/>
+ <stringAttribute key="BLD::Info|Tool|Librarian|sigs" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC32diab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPCFH:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC32gnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC32sfdiab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPCFS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC32sfgnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC403diab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPC403FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC403gnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC405diab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPC405FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC405gnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC405sfdiab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPC405FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC405sfgnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC440diab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPC440FH:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC440gnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC440sfdiab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPC440FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC440sfgnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC603diab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPC603FH:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC603gnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC604diab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPC604FH:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC604gnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC85XXdiab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPCE500FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC85XXgnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC85XXsfdiab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPCE500FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC85XXsfgnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC860sfdiab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tPPC860FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|PPC860sfgnu" value="echo "building $@";rm -f %OutFile%;nmppc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c ppc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|SIMLINUXdiab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c pentium > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tX86LH:vxworks63 -X -r5 -f 0x90,1,1 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|SIMLINUXgnu" value="echo "building $@";rm -f %OutFile%;nmpentium %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c pentium > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccpentium %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccpentium -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|SIMNTdiab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c pentium > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tX86LH:vxworks63 -X -r5 -f 0x90,1,1 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|SIMNTgnu" value="echo "building $@";rm -f %OutFile%;nmpentium %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c pentium > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccpentium %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccpentium -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|SIMSPARCSOLARISdiab" value="echo "building $@";rm -f %OutFile%;ddump -Ng %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c sparc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)dcc %DebugModeFlags% $(CC_ARCH_SPEC) -Xdollar-in-ident -Xforce-declarations $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)dld -tSPARCFH:vxworks63 -X -r5 %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|cmd|SIMSPARCSOLARISgnu" value="echo "building $@";rm -f %OutFile%;nmsparc %Objects% %Libraries% | tclsh $(WIND_BASE)/host/resource/hutils/tcl/munch.tcl -c sparc > $(OBJ_DIR)/ctdt.c;%ccompilerprefix% $(TOOL_PATH)ccsparc %DebugModeFlags% $(CC_ARCH_SPEC) -fdollars-in-identifiers -Wall $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o $(OBJ_DIR)/ctdt.o -c $(OBJ_DIR)/ctdt.c;%linkerprefix% $(TOOL_PATH)ccsparc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% $(OBJ_DIR)/ctdt.o %Objects% %Libraries% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC32diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC32gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC32sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC32sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC403diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC403gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC405diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC405gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC405sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC405sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC440diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC440gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC440sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC440sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC603diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC603gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC604diab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC604gnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC85XXdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC85XXgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC85XXsfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC85XXsfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC860sfdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|PPC860sfgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|SIMLINUXdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|SIMLINUXgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|SIMNTdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|SIMNTgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|SIMSPARCSOLARISdiab" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|dbgFlags|SIMSPARCSOLARISgnu" value="-g"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC32diab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC32gnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC32sfdiab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC32sfgnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC403diab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC403gnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC405diab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC405gnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC405sfdiab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC405sfgnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC440diab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC440gnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC440sfdiab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC440sfgnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC603diab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC603gnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC604diab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC604gnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC85XXdiab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC85XXgnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC85XXsfdiab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC85XXsfgnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC860sfdiab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|PPC860sfgnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|SIMLINUXdiab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|SIMLINUXgnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|SIMNTdiab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|SIMNTgnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|SIMSPARCSOLARISdiab" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|derivedSigs|SIMSPARCSOLARISgnu" value="*.out"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC32diab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC32gnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC32sfdiab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC32sfgnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC403diab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC403gnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC405diab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC405gnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC405sfdiab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC405sfgnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC440diab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC440gnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC440sfdiab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC440sfgnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC603diab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC603gnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC604diab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC604gnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC85XXdiab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC85XXgnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC85XXsfdiab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC85XXsfgnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC860sfdiab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|PPC860sfgnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|SIMLINUXdiab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|SIMLINUXgnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|SIMNTdiab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|SIMNTgnu" value="-T $(WIND_BASE)/target/h/tool/gnu/ldscripts/link.OUT"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|SIMSPARCSOLARISdiab" value="-r4"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|flags|SIMSPARCSOLARISgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC32diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC32gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC32sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC32sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC403diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC403gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC405diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC405gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC405sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC405sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC440diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC440gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC440sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC440sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC603diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC603gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC604diab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC604gnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC85XXdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC85XXgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC85XXsfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC85XXsfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC860sfdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|PPC860sfgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|SIMLINUXdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|SIMLINUXgnu" value="-O2 -nostdlib -fno-builtin -fno-defer-pop"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|SIMNTdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|SIMNTgnu" value="-O2 -nostdlib -fno-builtin -fno-defer-pop"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|SIMSPARCSOLARISdiab" value="-XO -Xsize-opt"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|nonDbgFlags|SIMSPARCSOLARISgnu" value="-O2 -fstrength-reduce -fno-builtin"/>
+ <booleanAttribute key="BLD::Info|Tool|Linker|object" value="false"/>
+ <booleanAttribute key="BLD::Info|Tool|Linker|passAble" value="false"/>
+ <stringAttribute key="BLD::Info|Tool|Linker|sigs" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC32diab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPCFH:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC32gnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC32sfdiab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPCFS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC32sfgnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC403diab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPC403FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC403gnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC405diab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPC405FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC405gnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC405sfdiab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPC405FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC405sfgnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC440diab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPC440FH:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC440gnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC440sfdiab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPC440FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC440sfgnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC603diab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPC603FH:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC603gnu" value="%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC604diab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPC604FH:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC604gnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC85XXdiab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPCE500FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC85XXgnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC85XXsfdiab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPCE500FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC85XXsfgnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC860sfdiab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tPPC860FS:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|PPC860sfgnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccppc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|SIMLINUXdiab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tX86LH:vxworks63 -X -r5 -f 0x90,1,1 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|SIMLINUXgnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccpentium -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|SIMNTdiab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tX86LH:vxworks63 -X -r5 -f 0x90,1,1 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|SIMNTgnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccpentium -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|SIMSPARCSOLARISdiab" value="echo "building $@";%linkerprefix% $(TOOL_PATH)dld -tSPARCFH:vxworks63 -X -r5 %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|cmd|SIMSPARCSOLARISgnu" value="echo "building $@";%linkerprefix% $(TOOL_PATH)ccsparc -r -nostdlib -Wl,-X %ToolFlags% -o %OutFile% %Objects% $(LIBPATH) $(LIBS) $(ADDED_LIBPATH) $(ADDED_LIBS) && if [ "$(EXPAND_DBG)" = "1" ]; then plink "$@";fi"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC32diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC32gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC32sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC32sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC403diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC403gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC405diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC405gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC405sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC405sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC440diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC440gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC440sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC440sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC603diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC603gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC604diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC604gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC85XXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC85XXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC85XXsfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC85XXsfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC860sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|PPC860sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|SIMLINUXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|SIMLINUXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|SIMNTdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|SIMNTgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|SIMSPARCSOLARISdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|dbgFlags|SIMSPARCSOLARISgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC32diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC32gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC32sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC32sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC403diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC403gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC405diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC405gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC405sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC405sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC440diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC440gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC440sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC440sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC603diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC603gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC604diab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC604gnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC85XXdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC85XXgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC85XXsfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC85XXsfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC860sfdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|PPC860sfgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|SIMLINUXdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|SIMLINUXgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|SIMNTdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|SIMNTgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|SIMSPARCSOLARISdiab" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|derivedSigs|SIMSPARCSOLARISgnu" value="*.o"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC32diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC32gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC32sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC32sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC403diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC403gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC405diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC405gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC405sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC405sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC440diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC440gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC440sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC440sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC603diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC603gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC604diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC604gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC85XXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC85XXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC85XXsfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC85XXsfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC860sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|PPC860sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|SIMLINUXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|SIMLINUXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|SIMNTdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|SIMNTgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|SIMSPARCSOLARISdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|flags|SIMSPARCSOLARISgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC32diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC32gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC32sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC32sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC403diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC403gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC405diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC405gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC405sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC405sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC440diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC440gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC440sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC440sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC603diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC603gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC604diab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC604gnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC85XXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC85XXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC85XXsfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC85XXsfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC860sfdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|PPC860sfgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|SIMLINUXdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|SIMLINUXgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|SIMNTdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|SIMNTgnu" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|SIMSPARCSOLARISdiab" value=""/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|nonDbgFlags|SIMSPARCSOLARISgnu" value=""/>
+ <booleanAttribute key="BLD::Info|Tool|Partial Image Linker|object" value="false"/>
+ <booleanAttribute key="BLD::Info|Tool|Partial Image Linker|passAble" value="true"/>
+ <stringAttribute key="BLD::Info|Tool|Partial Image Linker|sigs" value=""/>
+ <stringAttribute key="BLD::Info|cmd" value="%makeprefix% make --no-print-directory"/>
+ <stringAttribute key="BLD::Info|defaultSpec" value="PPC603gnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC32diab" value="PPC32diab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC32gnu" value="PPC32gnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC32sfdiab" value="PPC32sfdiab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC32sfgnu" value="PPC32sfgnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC403diab" value="PPC403diab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC403gnu" value="PPC403gnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC405diab" value="PPC405diab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC405gnu" value="PPC405gnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC405sfdiab" value="PPC405sfdiab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC405sfgnu" value="PPC405sfgnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC440diab" value="PPC440diab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC440gnu" value="PPC440gnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC440sfdiab" value="PPC440sfdiab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC440sfgnu" value="PPC440sfgnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC603diab" value="PPC603diab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC603gnu" value="PPC603gnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC604diab" value="PPC604diab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC604gnu" value="PPC604gnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC85XXdiab" value="PPC85XXdiab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC85XXgnu" value="PPC85XXgnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC85XXsfdiab" value="PPC85XXsfdiab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC85XXsfgnu" value="PPC85XXsfgnu"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC860sfdiab" value="PPC860sfdiab"/>
+ <stringAttribute key="BLD::Info|redirDir|PPC860sfgnu" value="PPC860sfgnu"/>
+ <stringAttribute key="BLD::Info|redirDir|SIMLINUXdiab" value="SIMLINUXdiab"/>
+ <stringAttribute key="BLD::Info|redirDir|SIMLINUXgnu" value="SIMLINUXgnu"/>
+ <stringAttribute key="BLD::Info|redirDir|SIMNTdiab" value="SIMNTdiab"/>
+ <stringAttribute key="BLD::Info|redirDir|SIMNTgnu" value="SIMNTgnu"/>
+ <stringAttribute key="BLD::Info|redirDir|SIMSPARCSOLARISdiab" value="SIMSPARCSOLARISdiab"/>
+ <stringAttribute key="BLD::Info|redirDir|SIMSPARCSOLARISgnu" value="SIMSPARCSOLARISgnu"/>
+ <stringAttribute key="BLD::Info|redirRoot" value=""/>
+ <intAttribute key="BLD::Info|refreshType" value="0"/>
+ <listAttribute key="BLD::Info|specs">
+ <stringAttribute value="PPC32diab"/>
+ <stringAttribute value="PPC32gnu"/>
+ <stringAttribute value="PPC32sfdiab"/>
+ <stringAttribute value="PPC32sfgnu"/>
+ <stringAttribute value="PPC403diab"/>
+ <stringAttribute value="PPC403gnu"/>
+ <stringAttribute value="PPC405diab"/>
+ <stringAttribute value="PPC405gnu"/>
+ <stringAttribute value="PPC405sfdiab"/>
+ <stringAttribute value="PPC405sfgnu"/>
+ <stringAttribute value="PPC440diab"/>
+ <stringAttribute value="PPC440gnu"/>
+ <stringAttribute value="PPC440sfdiab"/>
+ <stringAttribute value="PPC440sfgnu"/>
+ <stringAttribute value="PPC603diab"/>
+ <stringAttribute value="PPC603gnu"/>
+ <stringAttribute value="PPC604diab"/>
+ <stringAttribute value="PPC604gnu"/>
+ <stringAttribute value="PPC85XXdiab"/>
+ <stringAttribute value="PPC85XXgnu"/>
+ <stringAttribute value="PPC85XXsfdiab"/>
+ <stringAttribute value="PPC85XXsfgnu"/>
+ <stringAttribute value="PPC860sfdiab"/>
+ <stringAttribute value="PPC860sfgnu"/>
+ <stringAttribute value="SIMLINUXdiab"/>
+ <stringAttribute value="SIMLINUXgnu"/>
+ <stringAttribute value="SIMNTdiab"/>
+ <stringAttribute value="SIMNTgnu"/>
+ <stringAttribute value="SIMSPARCSOLARISdiab"/>
+ <stringAttribute value="SIMSPARCSOLARISgnu"/>
+ </listAttribute>
+ <listAttribute key="BLD::Tgt|Targets"/>
+ <intAttribute key="BuildSupportEnabled" value="1"/>
+ <listAttribute key="BuildSupportForBuildSpecs">
+ <stringAttribute value="PPC603gnu"/>
+ </listAttribute>
+ <booleanAttribute key="BuildTargetCentric" value="true"/>
+ <booleanAttribute key="PassObjects" value="false"/>
+ </mapAttribute>
+ </attributes>
+ <buildtargets>
+ <buildtarget buildtool="Librarian" name="WPILib" passed="true" targetname="WPILib">
+ <contents>
+ <folder name="/WPILib" recursive="true"/>
+ </contents>
+ </buildtarget>
+ <buildtarget buildtool="Librarian" name="JavaCameraLib" passed="false" targetname="JavaCameraLib">
+ <attributes>
+ <mapAttribute>
+ <stringAttribute key="BLD::Info|Tool|C++-Compiler|cmd|PPC603gnu" value="%cppcompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_C++FLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o %OutFile% -c %InFile%"/>
+ <stringAttribute key="BLD::Info|Tool|C-Compiler|cmd|PPC603gnu" value="echo "building $@";%ccompilerprefix% $(TOOL_PATH)ccppc %DebugModeFlags% %ToolFlags% $(ADDED_CFLAGS) %Includes% $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL $(DEFINES) -o %OutFile% -c %InFile%"/>
+ </mapAttribute>
+ </attributes>
+ <contents>
+ <file name="/WPILib/Vision/PCVideoServer.cpp"/>
+ <file name="/WPILib/Vision/AxisCamera.cpp"/>
+ <file name="/WPILib/Vision/AxisCameraParams.cpp"/>
+ <file name="/WPILib/Vision/EnumCameraParameter.cpp"/>
+ <file name="/WPILib/Vision/IntCameraParameter.cpp"/>
+ <file name="/WPILib/Error.cpp"/>
+ <file name="/WPILib/ErrorBase.cpp"/>
+ <file name="/WPILib/Task.cpp"/>
+ <file name="/WPILib/Timer.cpp"/>
+ <file name="/WPILib/Synchronized.cpp"/>
+ <file name="/WPILib/Utility.cpp"/>
+ </contents>
+ </buildtarget>
+ </buildtargets>
+</wrxml>
diff --git a/aos/externals/WPILib/WPILib/ADXL345_I2C.cpp b/aos/externals/WPILib/WPILib/ADXL345_I2C.cpp
new file mode 100644
index 0000000..9880e0e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ADXL345_I2C.cpp
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "ADXL345_I2C.h"
+#include "DigitalModule.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "I2C.h"
+
+const UINT8 ADXL345_I2C::kAddress;
+const UINT8 ADXL345_I2C::kPowerCtlRegister;
+const UINT8 ADXL345_I2C::kDataFormatRegister;
+const UINT8 ADXL345_I2C::kDataRegister;
+const double ADXL345_I2C::kGsPerLSB;
+
+/**
+ * Constructor.
+ *
+ * @param moduleNumber The digital module that the sensor is plugged into (1 or 2).
+ * @param range The range (+ or -) that the accelerometer will measure.
+ */
+ADXL345_I2C::ADXL345_I2C(UINT8 moduleNumber, ADXL345_I2C::DataFormat_Range range)
+ : m_i2c (NULL)
+{
+ DigitalModule *module = DigitalModule::GetInstance(moduleNumber);
+ if (module)
+ {
+ m_i2c = module->GetI2C(kAddress);
+
+ // Turn on the measurements
+ m_i2c->Write(kPowerCtlRegister, kPowerCtl_Measure);
+ // Specify the data format to read
+ m_i2c->Write(kDataFormatRegister, kDataFormat_FullRes | (UINT8)range);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_ADXL345, nUsageReporting::kADXL345_I2C, moduleNumber - 1);
+ }
+}
+
+/**
+ * Destructor.
+ */
+ADXL345_I2C::~ADXL345_I2C()
+{
+ delete m_i2c;
+ m_i2c = NULL;
+}
+
+/**
+ * Get the acceleration of one axis in Gs.
+ *
+ * @param axis The axis to read from.
+ * @return Acceleration of the ADXL345 in Gs.
+ */
+double ADXL345_I2C::GetAcceleration(ADXL345_I2C::Axes axis)
+{
+ INT16 rawAccel = 0;
+ if(m_i2c)
+ {
+ m_i2c->Read(kDataRegister + (UINT8)axis, sizeof(rawAccel), (UINT8 *)&rawAccel);
+
+ // Sensor is little endian... swap bytes
+ rawAccel = ((rawAccel >> 8) & 0xFF) | (rawAccel << 8);
+ }
+ return rawAccel * kGsPerLSB;
+}
+
+/**
+ * Get the acceleration of all axes in Gs.
+ *
+ * @return Acceleration measured on all axes of the ADXL345 in Gs.
+ */
+ADXL345_I2C::AllAxes ADXL345_I2C::GetAccelerations()
+{
+ AllAxes data = {0.0};
+ INT16 rawData[3];
+ if (m_i2c)
+ {
+ m_i2c->Read(kDataRegister, sizeof(rawData), (UINT8*)rawData);
+
+ // Sensor is little endian... swap bytes
+ for (INT32 i=0; i<3; i++)
+ {
+ rawData[i] = ((rawData[i] >> 8) & 0xFF) | (rawData[i] << 8);
+ }
+
+ data.XAxis = rawData[0] * kGsPerLSB;
+ data.YAxis = rawData[1] * kGsPerLSB;
+ data.ZAxis = rawData[2] * kGsPerLSB;
+ }
+ return data;
+}
+
diff --git a/aos/externals/WPILib/WPILib/ADXL345_I2C.h b/aos/externals/WPILib/WPILib/ADXL345_I2C.h
new file mode 100644
index 0000000..295ff3e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ADXL345_I2C.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __ADXL345_I2C_h__
+#define __ADXL345_I2C_h__
+
+#include "SensorBase.h"
+
+class I2C;
+
+/**
+ * ADXL345 Accelerometer on I2C.
+ *
+ * This class alows access to a Analog Devices ADXL345 3-axis accelerometer on an I2C bus.
+ * This class assumes the default (not alternate) sensor address of 0x3A (8-bit address).
+ */
+class ADXL345_I2C : public SensorBase
+{
+protected:
+ static const UINT8 kAddress = 0x3A;
+ static const UINT8 kPowerCtlRegister = 0x2D;
+ static const UINT8 kDataFormatRegister = 0x31;
+ static const UINT8 kDataRegister = 0x32;
+ static const double kGsPerLSB = 0.00390625;
+ enum PowerCtlFields {kPowerCtl_Link=0x20, kPowerCtl_AutoSleep=0x10, kPowerCtl_Measure=0x08, kPowerCtl_Sleep=0x04};
+ enum DataFormatFields {kDataFormat_SelfTest=0x80, kDataFormat_SPI=0x40, kDataFormat_IntInvert=0x20,
+ kDataFormat_FullRes=0x08, kDataFormat_Justify=0x04};
+
+public:
+ enum DataFormat_Range {kRange_2G=0x00, kRange_4G=0x01, kRange_8G=0x02, kRange_16G=0x03};
+ enum Axes {kAxis_X=0x00, kAxis_Y=0x02, kAxis_Z=0x04};
+ struct AllAxes
+ {
+ double XAxis;
+ double YAxis;
+ double ZAxis;
+ };
+
+public:
+ explicit ADXL345_I2C(UINT8 moduleNumber, DataFormat_Range range=kRange_2G);
+ virtual ~ADXL345_I2C();
+ virtual double GetAcceleration(Axes axis);
+ virtual AllAxes GetAccelerations();
+
+protected:
+ I2C* m_i2c;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/ADXL345_SPI.cpp b/aos/externals/WPILib/WPILib/ADXL345_SPI.cpp
new file mode 100644
index 0000000..789448d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ADXL345_SPI.cpp
@@ -0,0 +1,213 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "ADXL345_SPI.h"
+#include "DigitalInput.h"
+#include "DigitalOutput.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "SPI.h"
+
+const UINT8 ADXL345_SPI::kPowerCtlRegister;
+const UINT8 ADXL345_SPI::kDataFormatRegister;
+const UINT8 ADXL345_SPI::kDataRegister;
+const double ADXL345_SPI::kGsPerLSB;
+
+/**
+ * Constructor.
+ *
+ * @param clk The GPIO the clock signal is wired to.
+ * @param mosi The GPIO the MOSI (Master Out Slave In) signal is wired to.
+ * @param miso The GPIO the MISO (Master In Slave Out) signal is wired to.
+ * @param cs The GPIO the CS (Chip Select) signal is wired to.
+ * @param range The range (+ or -) that the accelerometer will measure.
+ */
+ADXL345_SPI::ADXL345_SPI(DigitalOutput &clk, DigitalOutput &mosi, DigitalInput &miso,
+ DigitalOutput &cs, DataFormat_Range range)
+ : m_clk (NULL)
+ , m_mosi (NULL)
+ , m_miso (NULL)
+ , m_cs (NULL)
+ , m_spi (NULL)
+{
+ Init(&clk, &mosi, &miso, &cs, range);
+}
+
+/**
+ * Constructor.
+ *
+ * @param clk The GPIO the clock signal is wired to.
+ * @param mosi The GPIO the MOSI (Master Out Slave In) signal is wired to.
+ * @param miso The GPIO the MISO (Master In Slave Out) signal is wired to.
+ * @param cs The GPIO the CS (Chip Select) signal is wired to.
+ * @param range The range (+ or -) that the accelerometer will measure.
+ */
+ADXL345_SPI::ADXL345_SPI(DigitalOutput *clk, DigitalOutput *mosi, DigitalInput *miso,
+ DigitalOutput *cs, DataFormat_Range range)
+ : m_clk (NULL)
+ , m_mosi (NULL)
+ , m_miso (NULL)
+ , m_cs (NULL)
+ , m_spi (NULL)
+{
+ Init(clk, mosi, miso, cs, range);
+}
+
+/**
+ * Constructor.
+ *
+ * @param moduleNumber The digital module with the sensor attached.
+ * @param clk The GPIO the clock signal is wired to.
+ * @param mosi The GPIO the MOSI (Master Out Slave In) signal is wired to.
+ * @param miso The GPIO the MISO (Master In Slave Out) signal is wired to.
+ * @param cs The GPIO the CS (Chip Select) signal is wired to.
+ * @param range The range (+ or -) that the accelerometer will measure.
+ */
+ADXL345_SPI::ADXL345_SPI(UINT8 moduleNumber, UINT32 clk, UINT32 mosi, UINT32 miso,
+ UINT32 cs, ADXL345_SPI::DataFormat_Range range)
+ : m_clk (NULL)
+ , m_mosi (NULL)
+ , m_miso (NULL)
+ , m_cs (NULL)
+ , m_spi (NULL)
+{
+ m_clk = new DigitalOutput(moduleNumber, clk);
+ m_mosi = new DigitalOutput(moduleNumber, mosi);
+ m_miso = new DigitalInput(moduleNumber, miso);
+ m_cs = new DigitalOutput(moduleNumber, cs);
+ Init(m_clk, m_mosi, m_miso, m_cs, range);
+}
+
+/**
+ * Internal common init function.
+ */
+void ADXL345_SPI::Init(DigitalOutput *clk, DigitalOutput *mosi, DigitalInput *miso,
+ DigitalOutput *cs, DataFormat_Range range)
+{
+ if (clk != NULL && mosi != NULL && miso != NULL && cs != NULL)
+ {
+ m_spi = new SPI(clk, mosi, miso);
+ m_spi->SetMSBFirst();
+ m_spi->SetSampleDataOnRising();
+ m_spi->SetSlaveSelect(cs, SPI::kChipSelect, false);
+ m_spi->SetClockActiveLow();
+ // 8-bit address and 8-bit data
+ m_spi->SetBitsPerWord(16);
+ m_spi->ApplyConfig();
+ m_spi->ClearReceivedData();
+
+ // Turn on the measurements
+ m_spi->Write((kPowerCtlRegister << 8) | kPowerCtl_Measure);
+ m_spi->Read();
+ // Specify the data format to read
+ m_spi->Write((kDataFormatRegister << 8) | kDataFormat_FullRes | (UINT8)(range & 0x03));
+ m_spi->Read();
+
+ // 8-bit address and 16-bit data
+ m_spi->SetBitsPerWord(24);
+ m_spi->ApplyConfig();
+
+ nUsageReporting::report(nUsageReporting::kResourceType_ADXL345, nUsageReporting::kADXL345_SPI);
+ }
+}
+
+/**
+ * Destructor.
+ */
+ADXL345_SPI::~ADXL345_SPI()
+{
+ delete m_spi;
+ m_spi = NULL;
+ delete m_cs;
+ m_cs = NULL;
+ delete m_miso;
+ m_miso = NULL;
+ delete m_mosi;
+ m_mosi = NULL;
+ delete m_clk;
+ m_clk = NULL;
+}
+
+/**
+ * Get the acceleration of one axis in Gs.
+ *
+ * @param axis The axis to read from.
+ * @return Acceleration of the ADXL345 in Gs.
+ */
+double ADXL345_SPI::GetAcceleration(ADXL345_SPI::Axes axis)
+{
+ INT16 rawAccel = 0;
+ if(m_spi)
+ {
+ m_spi->Write(((kAddress_Read | kAddress_MultiByte | kDataRegister) + (UINT8)axis) << 16);
+ rawAccel = (UINT16)m_spi->Read();
+
+ // Sensor is little endian... swap bytes
+ rawAccel = ((rawAccel >> 8) & 0xFF) | (rawAccel << 8);
+ }
+ return rawAccel * kGsPerLSB;
+}
+
+/**
+ * Get the acceleration of all axes in Gs.
+ *
+ * @return Acceleration measured on all axes of the ADXL345 in Gs.
+ */
+ADXL345_SPI::AllAxes ADXL345_SPI::GetAccelerations()
+{
+ AllAxes data = {0.0};
+ INT16 rawData[3];
+ if (m_spi)
+ {
+ SPI::tFrameMode mode;
+ bool activeLow;
+
+ // Backup original settings.
+ DigitalOutput *cs = m_spi->GetSlaveSelect(&mode, &activeLow);
+ UINT32 bitsPerWord = m_spi->GetBitsPerWord();
+
+ // Initialize the chip select to inactive.
+ cs->Set(activeLow);
+
+ // Control the chip select manually.
+ m_spi->SetSlaveSelect(NULL);
+ // 8-bit address
+ m_spi->SetBitsPerWord(8);
+ m_spi->ApplyConfig();
+
+ // Assert chip select.
+ cs->Set(!activeLow);
+
+ // Select the data address.
+ m_spi->Write(kAddress_Read | kAddress_MultiByte | kDataRegister);
+ m_spi->Read();
+
+ // 16-bits for each axis
+ m_spi->SetBitsPerWord(16);
+ m_spi->ApplyConfig();
+
+ for (INT32 i=0; i<3; i++)
+ {
+ // SPI Interface can't read enough data in a single transaction to read all axes at once.
+ rawData[i] = (UINT16)m_spi->Read(true);
+ // Sensor is little endian... swap bytes
+ rawData[i] = ((rawData[i] >> 8) & 0xFF) | (rawData[i] << 8);
+ }
+
+ // Deassert chip select.
+ cs->Set(activeLow);
+
+ // Restore original settings.
+ m_spi->SetSlaveSelect(cs, mode, activeLow);
+ m_spi->SetBitsPerWord(bitsPerWord);
+ m_spi->ApplyConfig();
+
+ data.XAxis = rawData[0] * kGsPerLSB;
+ data.YAxis = rawData[1] * kGsPerLSB;
+ data.ZAxis = rawData[2] * kGsPerLSB;
+ }
+ return data;
+}
+
diff --git a/aos/externals/WPILib/WPILib/ADXL345_SPI.h b/aos/externals/WPILib/WPILib/ADXL345_SPI.h
new file mode 100644
index 0000000..ab8ebde
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ADXL345_SPI.h
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __ADXL345_SPI_h__
+#define __ADXL345_SPI_h__
+
+#include "SensorBase.h"
+
+class DigitalInput;
+class DigitalOutput;
+class SPI;
+
+/**
+ * ADXL345 Accelerometer on SPI.
+ *
+ * This class alows access to an Analog Devices ADXL345 3-axis accelerometer via SPI.
+ * This class assumes the sensor is wired in 4-wire SPI mode.
+ */
+class ADXL345_SPI : public SensorBase
+{
+protected:
+ static const UINT8 kPowerCtlRegister = 0x2D;
+ static const UINT8 kDataFormatRegister = 0x31;
+ static const UINT8 kDataRegister = 0x32;
+ static const double kGsPerLSB = 0.00390625;
+ enum SPIAddressFields {kAddress_Read=0x80, kAddress_MultiByte=0x40};
+ enum PowerCtlFields {kPowerCtl_Link=0x20, kPowerCtl_AutoSleep=0x10, kPowerCtl_Measure=0x08, kPowerCtl_Sleep=0x04};
+ enum DataFormatFields {kDataFormat_SelfTest=0x80, kDataFormat_SPI=0x40, kDataFormat_IntInvert=0x20,
+ kDataFormat_FullRes=0x08, kDataFormat_Justify=0x04};
+
+public:
+ enum DataFormat_Range {kRange_2G=0x00, kRange_4G=0x01, kRange_8G=0x02, kRange_16G=0x03};
+ enum Axes {kAxis_X=0x00, kAxis_Y=0x02, kAxis_Z=0x04};
+ struct AllAxes
+ {
+ double XAxis;
+ double YAxis;
+ double ZAxis;
+ };
+
+public:
+ ADXL345_SPI(DigitalOutput &clk, DigitalOutput &mosi, DigitalInput &miso,
+ DigitalOutput &cs, DataFormat_Range range=kRange_2G);
+ ADXL345_SPI(DigitalOutput *clk, DigitalOutput *mosi, DigitalInput *miso,
+ DigitalOutput *cs, DataFormat_Range range=kRange_2G);
+ ADXL345_SPI(UINT8 moduleNumber, UINT32 clk, UINT32 mosi, UINT32 miso, UINT32 cs,
+ DataFormat_Range range=kRange_2G);
+ virtual ~ADXL345_SPI();
+ virtual double GetAcceleration(Axes axis);
+ virtual AllAxes GetAccelerations();
+
+protected:
+ void Init(DigitalOutput *clk, DigitalOutput *mosi, DigitalInput *miso,
+ DigitalOutput *cs, DataFormat_Range range);
+
+ DigitalOutput *m_clk;
+ DigitalOutput *m_mosi;
+ DigitalInput *m_miso;
+ DigitalOutput *m_cs;
+ SPI* m_spi;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Accelerometer.cpp b/aos/externals/WPILib/WPILib/Accelerometer.cpp
new file mode 100644
index 0000000..553404b
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Accelerometer.cpp
@@ -0,0 +1,127 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Accelerometer.h"
+#include "AnalogModule.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+
+/**
+ * Common function for initializing the accelerometer.
+ */
+void Accelerometer::InitAccelerometer()
+{
+ m_voltsPerG = 1.0;
+ m_zeroGVoltage = 2.5;
+ nUsageReporting::report(nUsageReporting::kResourceType_Accelerometer, m_analogChannel->GetChannel(), m_analogChannel->GetModuleNumber() - 1);
+}
+
+/**
+ * Create a new instance of an accelerometer.
+ *
+ * The accelerometer is assumed to be in the first analog module in the given analog channel. The
+ * constructor allocates desired analog channel.
+ */
+Accelerometer::Accelerometer(UINT32 channel)
+{
+ m_analogChannel = new AnalogChannel(channel);
+ m_allocatedChannel = true;
+ InitAccelerometer();
+}
+
+/**
+ * Create new instance of accelerometer.
+ *
+ * Make a new instance of the accelerometer given a module and channel. The constructor allocates
+ * the desired analog channel from the specified module
+ *
+ * @param moduleNumber The analog module (1 or 2).
+ * @param channel The analog channel (1..8)
+ */
+Accelerometer::Accelerometer(UINT8 moduleNumber, UINT32 channel)
+{
+ m_analogChannel = new AnalogChannel(moduleNumber, channel);
+ m_allocatedChannel = true;
+ InitAccelerometer();
+}
+
+/**
+ * Create a new instance of Accelerometer from an existing AnalogChannel.
+ * Make a new instance of accelerometer given an AnalogChannel. This is particularly
+ * useful if the port is going to be read as an analog channel as well as through
+ * the Accelerometer class.
+ */
+Accelerometer::Accelerometer(AnalogChannel *channel)
+{
+ if (channel == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ }
+ else
+ {
+ m_analogChannel = channel;
+ InitAccelerometer();
+ }
+ m_allocatedChannel = false;
+}
+
+/**
+ * Delete the analog components used for the accelerometer.
+ */
+Accelerometer::~Accelerometer()
+{
+ if (m_allocatedChannel)
+ {
+ delete m_analogChannel;
+ }
+}
+
+/**
+ * Return the acceleration in Gs.
+ *
+ * The acceleration is returned units of Gs.
+ *
+ * @return The current acceleration of the sensor in Gs.
+ */
+float Accelerometer::GetAcceleration()
+{
+ return (m_analogChannel->GetAverageVoltage() - m_zeroGVoltage) / m_voltsPerG;
+}
+
+/**
+ * Set the accelerometer sensitivity.
+ *
+ * This sets the sensitivity of the accelerometer used for calculating the acceleration.
+ * The sensitivity varys by accelerometer model. There are constants defined for various models.
+ *
+ * @param sensitivity The sensitivity of accelerometer in Volts per G.
+ */
+void Accelerometer::SetSensitivity(float sensitivity)
+{
+ m_voltsPerG = sensitivity;
+}
+
+/**
+ * Set the voltage that corresponds to 0 G.
+ *
+ * The zero G voltage varys by accelerometer model. There are constants defined for various models.
+ *
+ * @param zero The zero G voltage.
+ */
+void Accelerometer::SetZero(float zero)
+{
+ m_zeroGVoltage = zero;
+}
+
+/**
+ * Get the Acceleration for the PID Source parent.
+ *
+ * @return The current acceleration in Gs.
+ */
+double Accelerometer::PIDGet()
+{
+ return GetAcceleration();
+}
diff --git a/aos/externals/WPILib/WPILib/Accelerometer.h b/aos/externals/WPILib/WPILib/Accelerometer.h
new file mode 100644
index 0000000..aa0dca2
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Accelerometer.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef ACCELEROMETER_H_
+#define ACCELEROMETER_H_
+
+#include "AnalogChannel.h"
+#include "SensorBase.h"
+#include "PIDSource.h"
+
+/**
+ * Handle operation of the accelerometer.
+ * The accelerometer reads acceleration directly through the sensor. Many sensors have
+ * multiple axis and can be treated as multiple devices. Each is calibrated by finding
+ * the center value over a period of time.
+ */
+class Accelerometer : public SensorBase, public PIDSource {
+public:
+ explicit Accelerometer(UINT32 channel);
+ Accelerometer(UINT8 moduleNumber, UINT32 channel);
+ explicit Accelerometer(AnalogChannel *channel);
+ virtual ~Accelerometer();
+
+ float GetAcceleration();
+ void SetSensitivity(float sensitivity);
+ void SetZero(float zero);
+ double PIDGet();
+
+private:
+ void InitAccelerometer();
+
+ AnalogChannel *m_analogChannel;
+ float m_voltsPerG;
+ float m_zeroGVoltage;
+ bool m_allocatedChannel;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/AnalogChannel.cpp b/aos/externals/WPILib/WPILib/AnalogChannel.cpp
new file mode 100644
index 0000000..2da202c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/AnalogChannel.cpp
@@ -0,0 +1,434 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "AnalogChannel.h"
+#include "AnalogModule.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+static Resource *channels = NULL;
+
+const UINT8 AnalogChannel::kAccumulatorModuleNumber;
+const UINT32 AnalogChannel::kAccumulatorNumChannels;
+const UINT32 AnalogChannel::kAccumulatorChannels[] = {1, 2};
+
+/**
+ * Common initialization.
+ */
+void AnalogChannel::InitChannel(UINT8 moduleNumber, UINT32 channel)
+{
+ char buf[64];
+ Resource::CreateResourceObject(&channels, kAnalogModules * kAnalogChannels);
+ if (!CheckAnalogModule(moduleNumber))
+ {
+ snprintf(buf, 64, "Analog Module %d", moduleNumber);
+ wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf);
+ return;
+ }
+ if (!CheckAnalogChannel(channel))
+ {
+ snprintf(buf, 64, "Analog Channel %d", channel);
+ wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+ return;
+ }
+
+ snprintf(buf, 64, "Analog Input %d (Module: %d)", channel, moduleNumber);
+ if (channels->Allocate((moduleNumber - 1) * kAnalogChannels + channel - 1, buf) == ~0ul)
+ {
+ CloneError(channels);
+ return;
+ }
+ m_channel = channel;
+ m_module = AnalogModule::GetInstance(moduleNumber);
+ if (IsAccumulatorChannel())
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_accumulator = tAccumulator::create(channel - 1, &localStatus);
+ wpi_setError(localStatus);
+ m_accumulatorOffset=0;
+ }
+ else
+ {
+ m_accumulator = NULL;
+ }
+
+ nUsageReporting::report(nUsageReporting::kResourceType_AnalogChannel, channel, GetModuleNumber() - 1);
+}
+
+/**
+ * Construct an analog channel on a specified module.
+ *
+ * @param moduleNumber The analog module (1 or 2).
+ * @param channel The channel number to represent.
+ */
+AnalogChannel::AnalogChannel(UINT8 moduleNumber, UINT32 channel)
+{
+ InitChannel(moduleNumber, channel);
+}
+
+/**
+ * Construct an analog channel on the default module.
+ *
+ * @param channel The channel number to represent.
+ */
+AnalogChannel::AnalogChannel(UINT32 channel)
+{
+ InitChannel(GetDefaultAnalogModule(), channel);
+}
+
+/**
+ * Channel destructor.
+ */
+AnalogChannel::~AnalogChannel()
+{
+ channels->Free((m_module->GetNumber() - 1) * kAnalogChannels + m_channel - 1);
+}
+
+/**
+ * Get the analog module that this channel is on.
+ * @return A pointer to the AnalogModule that this channel is on.
+ */
+AnalogModule *AnalogChannel::GetModule()
+{
+ if (StatusIsFatal()) return NULL;
+ return m_module;
+}
+
+/**
+ * Get a sample straight from this channel on the module.
+ * The sample is a 12-bit value representing the -10V to 10V range of the A/D converter in the module.
+ * The units are in A/D converter codes. Use GetVoltage() to get the analog value in calibrated units.
+ * @return A sample straight from this channel on the module.
+ */
+INT16 AnalogChannel::GetValue()
+{
+ if (StatusIsFatal()) return 0;
+ return m_module->GetValue(m_channel);
+}
+
+/**
+ * Get a sample from the output of the oversample and average engine for this channel.
+ * The sample is 12-bit + the value configured in SetOversampleBits().
+ * The value configured in SetAverageBits() will cause this value to be averaged 2**bits number of samples.
+ * This is not a sliding window. The sample will not change until 2**(OversamplBits + AverageBits) samples
+ * have been acquired from the module on this channel.
+ * Use GetAverageVoltage() to get the analog value in calibrated units.
+ * @return A sample from the oversample and average engine for this channel.
+ */
+INT32 AnalogChannel::GetAverageValue()
+{
+ if (StatusIsFatal()) return 0;
+ return m_module->GetAverageValue(m_channel);
+}
+
+/**
+ * Get a scaled sample straight from this channel on the module.
+ * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset().
+ * @return A scaled sample straight from this channel on the module.
+ */
+float AnalogChannel::GetVoltage()
+{
+ if (StatusIsFatal()) return 0.0f;
+ return m_module->GetVoltage(m_channel);
+}
+
+/**
+ * Get a scaled sample from the output of the oversample and average engine for this channel.
+ * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset().
+ * Using oversampling will cause this value to be higher resolution, but it will update more slowly.
+ * Using averaging will cause this value to be more stable, but it will update more slowly.
+ * @return A scaled sample from the output of the oversample and average engine for this channel.
+ */
+float AnalogChannel::GetAverageVoltage()
+{
+ if (StatusIsFatal()) return 0.0f;
+ return m_module->GetAverageVoltage(m_channel);
+}
+
+/**
+ * Get the factory scaling least significant bit weight constant.
+ * The least significant bit weight constant for the channel that was calibrated in
+ * manufacturing and stored in an eeprom in the module.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @return Least significant bit weight.
+ */
+UINT32 AnalogChannel::GetLSBWeight()
+{
+ if (StatusIsFatal()) return 0;
+ return m_module->GetLSBWeight(m_channel);
+}
+
+/**
+ * Get the factory scaling offset constant.
+ * The offset constant for the channel that was calibrated in manufacturing and stored
+ * in an eeprom in the module.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @return Offset constant.
+ */
+INT32 AnalogChannel::GetOffset()
+{
+ if (StatusIsFatal()) return 0;
+ return m_module->GetOffset(m_channel);
+}
+
+/**
+ * Get the channel number.
+ * @return The channel number.
+ */
+UINT32 AnalogChannel::GetChannel()
+{
+ if (StatusIsFatal()) return 0;
+ return m_channel;
+}
+
+/**
+ * Get the module number.
+ * @return The module number.
+ */
+UINT8 AnalogChannel::GetModuleNumber()
+{
+ if (StatusIsFatal()) return 0;
+ return m_module->GetNumber();
+}
+
+/**
+ * Set the number of averaging bits.
+ * This sets the number of averaging bits. The actual number of averaged samples is 2**bits.
+ * Use averaging to improve the stability of your measurement at the expense of sampling rate.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @param bits Number of bits of averaging.
+ */
+void AnalogChannel::SetAverageBits(UINT32 bits)
+{
+ if (StatusIsFatal()) return;
+ m_module->SetAverageBits(m_channel, bits);
+}
+
+/**
+ * Get the number of averaging bits previously configured.
+ * This gets the number of averaging bits from the FPGA. The actual number of averaged samples is 2**bits.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @return Number of bits of averaging previously configured.
+ */
+UINT32 AnalogChannel::GetAverageBits()
+{
+ if (StatusIsFatal()) return 0;
+ return m_module->GetAverageBits(m_channel);
+}
+
+/**
+ * Set the number of oversample bits.
+ * This sets the number of oversample bits. The actual number of oversampled values is 2**bits.
+ * Use oversampling to improve the resolution of your measurements at the expense of sampling rate.
+ * The oversampling is done automatically in the FPGA.
+ *
+ * @param bits Number of bits of oversampling.
+ */
+void AnalogChannel::SetOversampleBits(UINT32 bits)
+{
+ if (StatusIsFatal()) return;
+ m_module->SetOversampleBits(m_channel, bits);
+}
+
+/**
+ * Get the number of oversample bits previously configured.
+ * This gets the number of oversample bits from the FPGA. The actual number of oversampled values is
+ * 2**bits. The oversampling is done automatically in the FPGA.
+ *
+ * @return Number of bits of oversampling previously configured.
+ */
+UINT32 AnalogChannel::GetOversampleBits()
+{
+ if (StatusIsFatal()) return 0;
+ return m_module->GetOversampleBits(m_channel);
+}
+
+/**
+ * Is the channel attached to an accumulator.
+ *
+ * @return The analog channel is attached to an accumulator.
+ */
+bool AnalogChannel::IsAccumulatorChannel()
+{
+ if (StatusIsFatal()) return false;
+ if(m_module->GetNumber() != kAccumulatorModuleNumber) return false;
+ for (UINT32 i=0; i<kAccumulatorNumChannels; i++)
+ {
+ if (m_channel == kAccumulatorChannels[i]) return true;
+ }
+ return false;
+}
+
+/**
+ * Initialize the accumulator.
+ */
+void AnalogChannel::InitAccumulator()
+{
+ if (StatusIsFatal()) return;
+ m_accumulatorOffset = 0;
+ SetAccumulatorCenter(0);
+ ResetAccumulator();
+}
+
+
+/**
+ * Set an inital value for the accumulator.
+ *
+ * This will be added to all values returned to the user.
+ * @param initialValue The value that the accumulator should start from when reset.
+ */
+void AnalogChannel::SetAccumulatorInitialValue(INT64 initialValue)
+{
+ if (StatusIsFatal()) return;
+ m_accumulatorOffset = initialValue;
+}
+
+/**
+ * Resets the accumulator to the initial value.
+ */
+void AnalogChannel::ResetAccumulator()
+{
+ if (StatusIsFatal()) return;
+ if (m_accumulator == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ return;
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_accumulator->strobeReset(&localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Set the center value of the accumulator.
+ *
+ * The center value is subtracted from each A/D value before it is added to the accumulator. This
+ * is used for the center value of devices like gyros and accelerometers to make integration work
+ * and to take the device offset into account when integrating.
+ *
+ * This center value is based on the output of the oversampled and averaged source from channel 1.
+ * Because of this, any non-zero oversample bits will affect the size of the value for this field.
+ */
+void AnalogChannel::SetAccumulatorCenter(INT32 center)
+{
+ if (StatusIsFatal()) return;
+ if (m_accumulator == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ return;
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_accumulator->writeCenter(center, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Set the accumulator's deadband.
+ */
+void AnalogChannel::SetAccumulatorDeadband(INT32 deadband)
+{
+ if (StatusIsFatal()) return;
+ if (m_accumulator == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ return;
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_accumulator->writeDeadband(deadband, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Read the accumulated value.
+ *
+ * Read the value that has been accumulating on channel 1.
+ * The accumulator is attached after the oversample and average engine.
+ *
+ * @return The 64-bit value accumulated since the last Reset().
+ */
+INT64 AnalogChannel::GetAccumulatorValue()
+{
+ if (StatusIsFatal()) return 0;
+ if (m_accumulator == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ return 0;
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ INT64 value = m_accumulator->readOutput_Value(&localStatus) + m_accumulatorOffset;
+ wpi_setError(localStatus);
+ return value;
+}
+
+/**
+ * Read the number of accumulated values.
+ *
+ * Read the count of the accumulated values since the accumulator was last Reset().
+ *
+ * @return The number of times samples from the channel were accumulated.
+ */
+UINT32 AnalogChannel::GetAccumulatorCount()
+{
+ if (StatusIsFatal()) return 0;
+ if (m_accumulator == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ return 0;
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 count = m_accumulator->readOutput_Count(&localStatus);
+ wpi_setError(localStatus);
+ return count;
+}
+
+
+/**
+ * Read the accumulated value and the number of accumulated values atomically.
+ *
+ * This function reads the value and count from the FPGA atomically.
+ * This can be used for averaging.
+ *
+ * @param value Pointer to the 64-bit accumulated output.
+ * @param count Pointer to the number of accumulation cycles.
+ */
+void AnalogChannel::GetAccumulatorOutput(INT64 *value, UINT32 *count)
+{
+ if (StatusIsFatal()) return;
+ if (m_accumulator == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ return;
+ }
+ if (value == NULL || count == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ return;
+ }
+
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ tAccumulator::tOutput output = m_accumulator->readOutput(&localStatus);
+ *value = output.Value + m_accumulatorOffset;
+ *count = output.Count;
+ wpi_setError(localStatus);
+}
+
+/**
+ * Get the Average voltage for the PID Source base object.
+ *
+ * @return The average voltage.
+ */
+double AnalogChannel::PIDGet()
+{
+ if (StatusIsFatal()) return 0.0;
+ return GetAverageValue();
+}
diff --git a/aos/externals/WPILib/WPILib/AnalogChannel.h b/aos/externals/WPILib/WPILib/AnalogChannel.h
new file mode 100644
index 0000000..c859555
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/AnalogChannel.h
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef ANALOG_CHANNEL_H_
+#define ANALOG_CHANNEL_H_
+
+#include "ChipObject.h"
+#include "SensorBase.h"
+#include "PIDSource.h"
+
+class AnalogModule;
+
+/**
+ * Analog channel class.
+ *
+ * Each analog channel is read from hardware as a 12-bit number representing -10V to 10V.
+ *
+ * Connected to each analog channel is an averaging and oversampling engine. This engine accumulates
+ * the specified ( by SetAverageBits() and SetOversampleBits() ) number of samples before returning a new
+ * value. This is not a sliding window average. The only difference between the oversampled samples and
+ * the averaged samples is that the oversampled samples are simply accumulated effectively increasing the
+ * resolution, while the averaged samples are divided by the number of samples to retain the resolution,
+ * but get more stable values.
+ */
+class AnalogChannel : public SensorBase, public PIDSource
+{
+public:
+ static const UINT8 kAccumulatorModuleNumber = 1;
+ static const UINT32 kAccumulatorNumChannels = 2;
+ static const UINT32 kAccumulatorChannels[kAccumulatorNumChannels];
+
+ AnalogChannel(UINT8 moduleNumber, UINT32 channel);
+ explicit AnalogChannel(UINT32 channel);
+ virtual ~AnalogChannel();
+
+ AnalogModule *GetModule();
+
+ INT16 GetValue();
+ INT32 GetAverageValue();
+
+ float GetVoltage();
+ float GetAverageVoltage();
+
+ UINT8 GetModuleNumber();
+ UINT32 GetChannel();
+
+ void SetAverageBits(UINT32 bits);
+ UINT32 GetAverageBits();
+ void SetOversampleBits(UINT32 bits);
+ UINT32 GetOversampleBits();
+
+ UINT32 GetLSBWeight();
+ INT32 GetOffset();
+
+ bool IsAccumulatorChannel();
+ void InitAccumulator();
+ void SetAccumulatorInitialValue(INT64 value);
+ void ResetAccumulator();
+ void SetAccumulatorCenter(INT32 center);
+ void SetAccumulatorDeadband(INT32 deadband);
+ INT64 GetAccumulatorValue();
+ UINT32 GetAccumulatorCount();
+ void GetAccumulatorOutput(INT64 *value, UINT32 *count);
+
+ double PIDGet();
+
+private:
+ void InitChannel(UINT8 moduleNumber, UINT32 channel);
+ UINT32 m_channel;
+ AnalogModule *m_module;
+ tAccumulator *m_accumulator;
+ INT64 m_accumulatorOffset;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/AnalogModule.cpp b/aos/externals/WPILib/WPILib/AnalogModule.cpp
new file mode 100644
index 0000000..d685c13
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/AnalogModule.cpp
@@ -0,0 +1,423 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "AnalogModule.h"
+#include "Synchronized.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+#include "NetworkCommunication/AICalibration.h"
+
+const long AnalogModule::kTimebase; ///< 40 MHz clock
+const long AnalogModule::kDefaultOversampleBits;
+const long AnalogModule::kDefaultAverageBits;
+const float AnalogModule::kDefaultSampleRate;
+SEM_ID AnalogModule::m_registerWindowSemaphore = NULL;
+
+/**
+ * Get an instance of an Analog Module.
+ *
+ * Singleton analog module creation where a module is allocated on the first use
+ * and the same module is returned on subsequent uses.
+ *
+ * @param moduleNumber The analog module to get (1 or 2).
+ * @return A pointer to the AnalogModule.
+ */
+AnalogModule* AnalogModule::GetInstance(UINT8 moduleNumber)
+{
+ if (CheckAnalogModule(moduleNumber))
+ {
+ return (AnalogModule*)GetModule(nLoadOut::kModuleType_Analog, moduleNumber);
+ }
+
+ // If this wasn't caught before now, make sure we say what's wrong before we crash
+ char buf[64];
+ snprintf(buf, 64, "Analog Module %d", moduleNumber);
+ wpi_setGlobalWPIErrorWithContext(ModuleIndexOutOfRange, buf);
+
+ return NULL;
+}
+
+/**
+ * Create a new instance of an analog module.
+ *
+ * Create an instance of the analog module object. Initialize all the parameters
+ * to reasonable values on start.
+ * Setting a global value on an analog module can be done only once unless subsequent
+ * values are set the previously set value.
+ * Analog modules are a singleton, so the constructor is never called outside of this class.
+ *
+ * @param moduleNumber The analog module to create (1 or 2).
+ */
+AnalogModule::AnalogModule(UINT8 moduleNumber)
+ : Module(nLoadOut::kModuleType_Analog, moduleNumber)
+ , m_module (NULL)
+ , m_sampleRateSet (false)
+ , m_numChannelsToActivate (0)
+{
+ AddToSingletonList();
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_module = tAI::create(m_moduleNumber - 1, &localStatus);
+ wpi_setError(localStatus);
+ SetNumChannelsToActivate(kAnalogChannels);
+ SetSampleRate(kDefaultSampleRate);
+
+ for (UINT32 i = 0; i < kAnalogChannels; i++)
+ {
+ m_module->writeScanList(i, i, &localStatus);
+ wpi_setError(localStatus);
+ SetAverageBits(i + 1, kDefaultAverageBits);
+ SetOversampleBits(i + 1, kDefaultOversampleBits);
+ }
+
+ if (m_registerWindowSemaphore == NULL)
+ {
+ // Needs to be global since the protected resource spans both module singletons.
+ m_registerWindowSemaphore = semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+ }
+}
+
+/**
+ * Destructor for AnalogModule.
+ */
+AnalogModule::~AnalogModule()
+{
+ delete m_module;
+}
+
+/**
+ * Set the sample rate on the module.
+ *
+ * This is a global setting for the module and effects all channels.
+ *
+ * @param samplesPerSecond The number of samples per channel per second.
+ */
+void AnalogModule::SetSampleRate(float samplesPerSecond)
+{
+ // TODO: This will change when variable size scan lists are implemented.
+ // TODO: Need float comparison with epsilon.
+ //wpi_assert(!sampleRateSet || GetSampleRate() == samplesPerSecond);
+ m_sampleRateSet = true;
+
+ // Compute the convert rate
+ UINT32 ticksPerSample = (UINT32)((float)kTimebase / samplesPerSecond);
+ UINT32 ticksPerConversion = ticksPerSample / GetNumChannelsToActivate();
+ // ticksPerConversion must be at least 80
+ if (ticksPerConversion < 80)
+ {
+ wpi_setWPIError(SampleRateTooHigh);
+ ticksPerConversion = 80;
+ }
+
+ // Atomically set the scan size and the convert rate so that the sample rate is constant
+ tAI::tConfig config;
+ config.ScanSize = GetNumChannelsToActivate();
+ config.ConvertRate = ticksPerConversion;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_module->writeConfig(config, &localStatus);
+ wpi_setError(localStatus);
+
+ // Indicate that the scan size has been commited to hardware.
+ SetNumChannelsToActivate(0);
+}
+
+/**
+ * Get the current sample rate on the module.
+ *
+ * This assumes one entry in the scan list.
+ * This is a global setting for the module and effects all channels.
+ *
+ * @return Sample rate.
+ */
+float AnalogModule::GetSampleRate()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 ticksPerConversion = m_module->readLoopTiming(&localStatus);
+ wpi_setError(localStatus);
+ UINT32 ticksPerSample = ticksPerConversion * GetNumActiveChannels();
+ return (float)kTimebase / (float)ticksPerSample;
+}
+
+/**
+ * Return the number of channels on the module in use.
+ *
+ * @return Active channels.
+ */
+UINT32 AnalogModule::GetNumActiveChannels()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 scanSize = m_module->readConfig_ScanSize(&localStatus);
+ wpi_setError(localStatus);
+ if (scanSize == 0)
+ return 8;
+ return scanSize;
+}
+
+/**
+ * Get the number of active channels.
+ *
+ * This is an internal function to allow the atomic update of both the
+ * number of active channels and the sample rate.
+ *
+ * When the number of channels changes, use the new value. Otherwise,
+ * return the curent value.
+ *
+ * @return Value to write to the active channels field.
+ */
+UINT32 AnalogModule::GetNumChannelsToActivate()
+{
+ if(m_numChannelsToActivate == 0) return GetNumActiveChannels();
+ return m_numChannelsToActivate;
+}
+
+/**
+ * Set the number of active channels.
+ *
+ * Store the number of active channels to set. Don't actually commit to hardware
+ * until SetSampleRate().
+ *
+ * @param channels Number of active channels.
+ */
+void AnalogModule::SetNumChannelsToActivate(UINT32 channels)
+{
+ m_numChannelsToActivate = channels;
+}
+
+/**
+ * Set the number of averaging bits.
+ *
+ * This sets the number of averaging bits. The actual number of averaged samples is 2**bits.
+ * Use averaging to improve the stability of your measurement at the expense of sampling rate.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @param channel Analog channel to configure.
+ * @param bits Number of bits to average.
+ */
+void AnalogModule::SetAverageBits(UINT32 channel, UINT32 bits)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_module->writeAverageBits(channel - 1, bits, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Get the number of averaging bits.
+ *
+ * This gets the number of averaging bits from the FPGA. The actual number of averaged samples is 2**bits.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @param channel Channel to address.
+ * @return Bits to average.
+ */
+UINT32 AnalogModule::GetAverageBits(UINT32 channel)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 result = m_module->readAverageBits(channel - 1, &localStatus);
+ wpi_setError(localStatus);
+ return result;
+}
+
+/**
+ * Set the number of oversample bits.
+ *
+ * This sets the number of oversample bits. The actual number of oversampled values is 2**bits.
+ * Use oversampling to improve the resolution of your measurements at the expense of sampling rate.
+ * The oversampling is done automatically in the FPGA.
+ *
+ * @param channel Analog channel to configure.
+ * @param bits Number of bits to oversample.
+ */
+void AnalogModule::SetOversampleBits(UINT32 channel, UINT32 bits)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_module->writeOversampleBits(channel - 1, bits, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Get the number of oversample bits.
+ *
+ * This gets the number of oversample bits from the FPGA. The actual number of oversampled values is
+ * 2**bits. The oversampling is done automatically in the FPGA.
+ *
+ * @param channel Channel to address.
+ * @return Bits to oversample.
+ */
+UINT32 AnalogModule::GetOversampleBits(UINT32 channel)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 result = m_module->readOversampleBits(channel - 1, &localStatus);
+ wpi_setError(localStatus);
+ return result;
+}
+
+/**
+ * Get a sample straight from the channel on this module.
+ *
+ * The sample is a 12-bit value representing the -10V to 10V range of the A/D converter in the module.
+ * The units are in A/D converter codes. Use GetVoltage() to get the analog value in calibrated units.
+ *
+ * @return A sample straight from the channel on this module.
+ */
+INT16 AnalogModule::GetValue(UINT32 channel)
+{
+ INT16 value;
+ CheckAnalogChannel(channel);
+
+ tAI::tReadSelect readSelect;
+ readSelect.Channel = channel - 1;
+ readSelect.Module = m_moduleNumber - 1;
+ readSelect.Averaged = false;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+
+ {
+ Synchronized sync(m_registerWindowSemaphore);
+ m_module->writeReadSelect(readSelect, &localStatus);
+ m_module->strobeLatchOutput(&localStatus);
+ value = (INT16) m_module->readOutput(&localStatus);
+ }
+
+ wpi_setError(localStatus);
+ return value;
+}
+
+/**
+ * Get a sample from the output of the oversample and average engine for the channel.
+ *
+ * The sample is 12-bit + the value configured in SetOversampleBits().
+ * The value configured in SetAverageBits() will cause this value to be averaged 2**bits number of samples.
+ * This is not a sliding window. The sample will not change until 2**(OversamplBits + AverageBits) samples
+ * have been acquired from the module on this channel.
+ * Use GetAverageVoltage() to get the analog value in calibrated units.
+ *
+ * @param channel Channel number to read.
+ * @return A sample from the oversample and average engine for the channel.
+ */
+INT32 AnalogModule::GetAverageValue(UINT32 channel)
+{
+ INT32 value;
+ CheckAnalogChannel(channel);
+
+ tAI::tReadSelect readSelect;
+ readSelect.Channel = channel - 1;
+ readSelect.Module = m_moduleNumber - 1;
+ readSelect.Averaged = true;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+
+ {
+ Synchronized sync(m_registerWindowSemaphore);
+ m_module->writeReadSelect(readSelect, &localStatus);
+ m_module->strobeLatchOutput(&localStatus);
+ value = m_module->readOutput(&localStatus);
+ }
+
+ wpi_setError(localStatus);
+ return value;
+}
+
+/**
+ * Convert a voltage to a raw value for a specified channel.
+ *
+ * This process depends on the calibration of each channel, so the channel
+ * must be specified.
+ *
+ * @todo This assumes raw values. Oversampling not supported as is.
+ *
+ * @param channel The channel to convert for.
+ * @param voltage The voltage to convert.
+ * @return The raw value for the channel.
+ */
+INT32 AnalogModule::VoltsToValue(INT32 channel, float voltage)
+{
+ if (voltage > 10.0)
+ {
+ voltage = 10.0;
+ wpi_setWPIError(VoltageOutOfRange);
+ }
+ if (voltage < -10.0)
+ {
+ voltage = -10.0;
+ wpi_setWPIError(VoltageOutOfRange);
+ }
+ UINT32 LSBWeight = GetLSBWeight(channel);
+ INT32 offset = GetOffset(channel);
+ INT32 value = (INT32) ((voltage + offset * 1.0e-9) / (LSBWeight * 1.0e-9));
+ return value;
+}
+
+/**
+ * Get a scaled sample straight from the channel on this module.
+ *
+ * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset().
+ *
+ * @param channel The channel to read.
+ * @return A scaled sample straight from the channel on this module.
+ */
+float AnalogModule::GetVoltage(UINT32 channel)
+{
+ INT16 value = GetValue(channel);
+ UINT32 LSBWeight = GetLSBWeight(channel);
+ INT32 offset = GetOffset(channel);
+ float voltage = LSBWeight * 1.0e-9 * value - offset * 1.0e-9;
+ return voltage;
+}
+
+/**
+ * Get a scaled sample from the output of the oversample and average engine for the channel.
+ *
+ * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset().
+ * Using oversampling will cause this value to be higher resolution, but it will update more slowly.
+ * Using averaging will cause this value to be more stable, but it will update more slowly.
+ *
+ * @param channel The channel to read.
+ * @return A scaled sample from the output of the oversample and average engine for the channel.
+ */
+float AnalogModule::GetAverageVoltage(UINT32 channel)
+{
+ INT32 value = GetAverageValue(channel);
+ UINT32 LSBWeight = GetLSBWeight(channel);
+ INT32 offset = GetOffset(channel);
+ UINT32 oversampleBits = GetOversampleBits(channel);
+ float voltage = ((LSBWeight * 1.0e-9 * value) / (float)(1 << oversampleBits)) - offset * 1.0e-9;
+ return voltage;
+}
+
+/**
+ * Get the factory scaling least significant bit weight constant.
+ * The least significant bit weight constant for the channel that was calibrated in
+ * manufacturing and stored in an eeprom in the module.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @param channel The channel to get calibration data for.
+ * @return Least significant bit weight.
+ */
+UINT32 AnalogModule::GetLSBWeight(UINT32 channel)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 lsbWeight = FRC_NetworkCommunication_nAICalibration_getLSBWeight(m_module->getSystemIndex(), channel - 1, (INT32*)&localStatus);
+ wpi_setError(localStatus);
+ return lsbWeight;
+}
+
+/**
+ * Get the factory scaling offset constant.
+ * The offset constant for the channel that was calibrated in manufacturing and stored
+ * in an eeprom in the module.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @param channel The channel to get calibration data for.
+ * @return Offset constant.
+ */
+INT32 AnalogModule::GetOffset(UINT32 channel)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ INT32 offset = FRC_NetworkCommunication_nAICalibration_getOffset(m_module->getSystemIndex(), channel - 1, (INT32*)&localStatus);
+ wpi_setError(localStatus);
+ return offset;
+}
+
+
diff --git a/aos/externals/WPILib/WPILib/AnalogModule.h b/aos/externals/WPILib/WPILib/AnalogModule.h
new file mode 100644
index 0000000..3f69685
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/AnalogModule.h
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef ANALOG_MODULE_H_
+#define ANALOG_MODULE_H_
+
+#include "ChipObject.h"
+#include "Module.h"
+
+/**
+ * Analog Module class.
+ * Each module can independently sample its channels at a configurable rate.
+ * There is a 64-bit hardware accumulator associated with channel 1 on each module.
+ * The accumulator is attached to the output of the oversample and average engine so that the center
+ * value can be specified in higher resolution resulting in less error.
+ */
+class AnalogModule: public Module
+{
+ friend class Module;
+
+public:
+ static const long kTimebase = 40000000; ///< 40 MHz clock
+ static const long kDefaultOversampleBits = 0;
+ static const long kDefaultAverageBits = 7;
+ static const float kDefaultSampleRate = 50000.0;
+
+ void SetSampleRate(float samplesPerSecond);
+ float GetSampleRate();
+ void SetAverageBits(UINT32 channel, UINT32 bits);
+ UINT32 GetAverageBits(UINT32 channel);
+ void SetOversampleBits(UINT32 channel, UINT32 bits);
+ UINT32 GetOversampleBits(UINT32 channel);
+ INT16 GetValue(UINT32 channel);
+ INT32 GetAverageValue(UINT32 channel);
+ float GetAverageVoltage(UINT32 channel);
+ float GetVoltage(UINT32 channel);
+ UINT32 GetLSBWeight(UINT32 channel);
+ INT32 GetOffset(UINT32 channel);
+ INT32 VoltsToValue(INT32 channel, float voltage);
+
+ static AnalogModule* GetInstance(UINT8 moduleNumber);
+
+protected:
+ explicit AnalogModule(UINT8 moduleNumber);
+ virtual ~AnalogModule();
+
+private:
+ static SEM_ID m_registerWindowSemaphore;
+
+ UINT32 GetNumActiveChannels();
+ UINT32 GetNumChannelsToActivate();
+ void SetNumChannelsToActivate(UINT32 channels);
+
+ tAI *m_module;
+ bool m_sampleRateSet;
+ UINT32 m_numChannelsToActivate;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/AnalogTrigger.cpp b/aos/externals/WPILib/WPILib/AnalogTrigger.cpp
new file mode 100644
index 0000000..ffe45c1
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/AnalogTrigger.cpp
@@ -0,0 +1,200 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "AnalogTrigger.h"
+
+#include "AnalogChannel.h"
+#include "AnalogModule.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+static Resource *triggers = NULL;
+
+/**
+ * Initialize an analog trigger from a slot and channel.
+ * This is the common code for the two constructors that use a slot and channel.
+ */
+void AnalogTrigger::InitTrigger(UINT8 moduleNumber, UINT32 channel)
+{
+ Resource::CreateResourceObject(&triggers, tAnalogTrigger::kNumSystems);
+ UINT32 index = triggers->Allocate("Analog Trigger");
+ if (index == ~0ul)
+ {
+ CloneError(triggers);
+ return;
+ }
+ m_index = (UINT8)index;
+ m_channel = channel;
+ m_analogModule = AnalogModule::GetInstance(moduleNumber);
+
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_trigger = tAnalogTrigger::create(m_index, &localStatus);
+ m_trigger->writeSourceSelect_Channel(m_channel - 1, &localStatus);
+ m_trigger->writeSourceSelect_Module(moduleNumber - 1, &localStatus);
+ wpi_setError(localStatus);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_AnalogTrigger, m_channel, moduleNumber - 1);
+}
+
+/**
+ * Constructor for an analog trigger given a channel number.
+ * The default module is used in this case.
+ *
+ * @param channel The analog channel (1..8).
+ */
+AnalogTrigger::AnalogTrigger(UINT32 channel)
+{
+ InitTrigger(GetDefaultAnalogModule(), channel);
+}
+
+/**
+ * Constructor for an analog trigger given both the slot and channel.
+ *
+ * @param moduleNumber The analog module (1 or 2).
+ * @param channel The analog channel (1..8).
+ */
+AnalogTrigger::AnalogTrigger(UINT8 moduleNumber, UINT32 channel)
+{
+ InitTrigger(moduleNumber, channel);
+}
+
+/**
+ * Construct an analog trigger given an analog channel.
+ * This should be used in the case of sharing an analog channel between the trigger
+ * and an analog input object.
+ */
+AnalogTrigger::AnalogTrigger(AnalogChannel *channel)
+{
+ InitTrigger(channel->GetModuleNumber(), channel->GetChannel());
+}
+
+AnalogTrigger::~AnalogTrigger()
+{
+ triggers->Free(m_index);
+ delete m_trigger;
+}
+
+/**
+ * Set the upper and lower limits of the analog trigger.
+ * The limits are given in ADC codes. If oversampling is used, the units must be scaled
+ * appropriately.
+ */
+void AnalogTrigger::SetLimitsRaw(INT32 lower, INT32 upper)
+{
+ if (StatusIsFatal()) return;
+ if (lower > upper)
+ {
+ wpi_setWPIError(AnalogTriggerLimitOrderError);
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_trigger->writeLowerLimit(lower, &localStatus);
+ m_trigger->writeUpperLimit(upper, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Set the upper and lower limits of the analog trigger.
+ * The limits are given as floating point voltage values.
+ */
+void AnalogTrigger::SetLimitsVoltage(float lower, float upper)
+{
+ if (StatusIsFatal()) return;
+ if (lower > upper)
+ {
+ wpi_setWPIError(AnalogTriggerLimitOrderError);
+ }
+ // TODO: This depends on the averaged setting. Only raw values will work as is.
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_trigger->writeLowerLimit(m_analogModule->VoltsToValue(m_channel, lower), &localStatus);
+ m_trigger->writeUpperLimit(m_analogModule->VoltsToValue(m_channel, upper), &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Configure the analog trigger to use the averaged vs. raw values.
+ * If the value is true, then the averaged value is selected for the analog trigger, otherwise
+ * the immediate value is used.
+ */
+void AnalogTrigger::SetAveraged(bool useAveragedValue)
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ if (m_trigger->readSourceSelect_Filter(&localStatus) != 0)
+ wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not support average and filtering at the same time.");
+ m_trigger->writeSourceSelect_Averaged(useAveragedValue, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Configure the analog trigger to use a filtered value.
+ * The analog trigger will operate with a 3 point average rejection filter. This is designed to
+ * help with 360 degree pot applications for the period where the pot crosses through zero.
+ */
+void AnalogTrigger::SetFiltered(bool useFilteredValue)
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ if (m_trigger->readSourceSelect_Averaged(&localStatus) != 0)
+ wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not support average and filtering at the same time.");
+ m_trigger->writeSourceSelect_Filter(useFilteredValue, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Return the index of the analog trigger.
+ * This is the FPGA index of this analog trigger instance.
+ * @return The index of the analog trigger.
+ */
+UINT32 AnalogTrigger::GetIndex()
+{
+ if (StatusIsFatal()) return ~0ul;
+ return m_index;
+}
+
+/**
+ * Return the InWindow output of the analog trigger.
+ * True if the analog input is between the upper and lower limits.
+ * @return The InWindow output of the analog trigger.
+ */
+bool AnalogTrigger::GetInWindow()
+{
+ if (StatusIsFatal()) return false;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool result = m_trigger->readOutput_InHysteresis(m_index, &localStatus) != 0;
+ wpi_setError(localStatus);
+ return result;
+}
+
+/**
+ * Return the TriggerState output of the analog trigger.
+ * True if above upper limit.
+ * False if below lower limit.
+ * If in Hysteresis, maintain previous state.
+ * @return The TriggerState output of the analog trigger.
+ */
+bool AnalogTrigger::GetTriggerState()
+{
+ if (StatusIsFatal()) return false;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool result = m_trigger->readOutput_OverLimit(m_index, &localStatus) != 0;
+ wpi_setError(localStatus);
+ return result;
+}
+
+/**
+ * Creates an AnalogTriggerOutput object.
+ * Gets an output object that can be used for routing.
+ * Caller is responsible for deleting the AnalogTriggerOutput object.
+ * @param type An enum of the type of output object to create.
+ * @return A pointer to a new AnalogTriggerOutput object.
+ */
+AnalogTriggerOutput *AnalogTrigger::CreateOutput(AnalogTriggerOutput::Type type)
+{
+ if (StatusIsFatal()) return NULL;
+ return new AnalogTriggerOutput(this, type);
+}
+
diff --git a/aos/externals/WPILib/WPILib/AnalogTrigger.h b/aos/externals/WPILib/WPILib/AnalogTrigger.h
new file mode 100644
index 0000000..2975be4
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/AnalogTrigger.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef ANALOG_TRIGGER_H_
+#define ANALOG_TRIGGER_H_
+
+#include "AnalogTriggerOutput.h"
+#include "SensorBase.h"
+
+class AnalogChannel;
+class AnalogModule;
+
+class AnalogTrigger: public SensorBase
+{
+ friend class AnalogTriggerOutput;
+public:
+ AnalogTrigger(UINT8 moduleNumber, UINT32 channel);
+ explicit AnalogTrigger(UINT32 channel);
+ explicit AnalogTrigger(AnalogChannel *channel);
+ virtual ~AnalogTrigger();
+
+ void SetLimitsVoltage(float lower, float upper);
+ void SetLimitsRaw(INT32 lower, INT32 upper);
+ void SetAveraged(bool useAveragedValue);
+ void SetFiltered(bool useFilteredValue);
+ UINT32 GetIndex();
+ bool GetInWindow();
+ bool GetTriggerState();
+ AnalogTriggerOutput *CreateOutput(AnalogTriggerOutput::Type type);
+
+private:
+ void InitTrigger(UINT8 moduleNumber, UINT32 channel);
+
+ UINT8 m_index;
+ tAnalogTrigger *m_trigger;
+ AnalogModule *m_analogModule;
+ UINT32 m_channel;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/AnalogTriggerOutput.cpp b/aos/externals/WPILib/WPILib/AnalogTriggerOutput.cpp
new file mode 100644
index 0000000..89bf448
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/AnalogTriggerOutput.cpp
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "AnalogTriggerOutput.h"
+#include "AnalogTrigger.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+
+/**
+ * Create an object that represents one of the four outputs from an analog trigger.
+ *
+ * Because this class derives from DigitalSource, it can be passed into routing functions
+ * for Counter, Encoder, etc.
+ *
+ * @param trigger A pointer to the trigger for which this is an output.
+ * @param outputType An enum that specifies the output on the trigger to represent.
+ */
+AnalogTriggerOutput::AnalogTriggerOutput(AnalogTrigger *trigger, AnalogTriggerOutput::Type outputType)
+ : m_trigger (trigger)
+ , m_outputType (outputType)
+{
+ nUsageReporting::report(nUsageReporting::kResourceType_AnalogTriggerOutput, trigger->GetIndex(), outputType);
+}
+
+AnalogTriggerOutput::~AnalogTriggerOutput()
+{
+}
+
+/**
+ * Get the state of the analog trigger output.
+ * @return The state of the analog trigger output.
+ */
+bool AnalogTriggerOutput::Get()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool result = false;
+ switch(m_outputType)
+ {
+ case kInWindow:
+ result = m_trigger->m_trigger->readOutput_InHysteresis(m_trigger->m_index, &localStatus);
+ case kState:
+ result = m_trigger->m_trigger->readOutput_OverLimit(m_trigger->m_index, &localStatus);
+ case kRisingPulse:
+ case kFallingPulse:
+ wpi_setWPIError(AnalogTriggerPulseOutputError);
+ return false;
+ }
+ wpi_setError(localStatus);
+ return result;
+}
+
+/**
+ * @return The value to be written to the channel field of a routing mux.
+ */
+UINT32 AnalogTriggerOutput::GetChannelForRouting()
+{
+ return (m_trigger->m_index << 2) + m_outputType;
+}
+
+/**
+ * @return The value to be written to the module field of a routing mux.
+ */
+UINT32 AnalogTriggerOutput::GetModuleForRouting()
+{
+ return m_trigger->m_index >> 2;
+}
+
+/**
+ * @return The value to be written to the module field of a routing mux.
+ */
+bool AnalogTriggerOutput::GetAnalogTriggerForRouting()
+{
+ return true;
+}
+
+/**
+ * Request interrupts asynchronously on this analog trigger output.
+ * TODO: Hardware supports interrupts on Analog Trigger outputs... WPILib should too
+ */
+void AnalogTriggerOutput::RequestInterrupts(tInterruptHandler handler, void *param)
+{
+}
+
+/**
+ * Request interrupts synchronously on this analog trigger output.
+ * TODO: Hardware supports interrupts on Analog Trigger outputs... WPILib should too
+ */
+void AnalogTriggerOutput::RequestInterrupts()
+{
+}
+
diff --git a/aos/externals/WPILib/WPILib/AnalogTriggerOutput.h b/aos/externals/WPILib/WPILib/AnalogTriggerOutput.h
new file mode 100644
index 0000000..53dc88a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/AnalogTriggerOutput.h
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef ANALOG_TRIGGER_OUTPUT_H_
+#define ANALOG_TRIGGER_OUTPUT_H_
+
+#include "DigitalSource.h"
+
+class AnalogTrigger;
+
+/**
+ * Class to represent a specific output from an analog trigger.
+ * This class is used to get the current output value and also as a DigitalSource
+ * to provide routing of an output to digital subsystems on the FPGA such as
+ * Counter, Encoder, and Interrupt.
+ *
+ * The TriggerState output indicates the primary output value of the trigger. If the analog
+ * signal is less than the lower limit, the output is false. If the analog value is greater
+ * than the upper limit, then the output is true. If the analog value is in between, then
+ * the trigger output state maintains its most recent value.
+ *
+ * The InWindow output indicates whether or not the analog signal is inside the range defined
+ * by the limits.
+ *
+ * The RisingPulse and FallingPulse outputs detect an instantaneous transition from above the
+ * upper limit to below the lower limit, and vise versa. These pulses represent a rollover
+ * condition of a sensor and can be routed to an up / down couter or to interrupts. Because
+ * the outputs generate a pulse, they cannot be read directly. To help ensure that a rollover
+ * condition is not missed, there is an average rejection filter available that operates on the
+ * upper 8 bits of a 12 bit number and selects the nearest outlyer of 3 samples. This will reject
+ * a sample that is (due to averaging or sampling) errantly between the two limits. This filter
+ * will fail if more than one sample in a row is errantly in between the two limits. You may see
+ * this problem if attempting to use this feature with a mechanical rollover sensor, such as a
+ * 360 degree no-stop potentiometer without signal conditioning, because the rollover transition
+ * is not sharp / clean enough. Using the averaging engine may help with this, but rotational speeds of
+ * the sensor will then be limited.
+ */
+class AnalogTriggerOutput: public DigitalSource
+{
+ friend class AnalogTrigger;
+public:
+ typedef enum {kInWindow=0, kState=1, kRisingPulse=2, kFallingPulse=3} Type;
+
+ virtual ~AnalogTriggerOutput();
+ bool Get();
+
+ // DigitalSource interface
+ virtual UINT32 GetChannelForRouting();
+ virtual UINT32 GetModuleForRouting();
+ virtual bool GetAnalogTriggerForRouting();
+ virtual void RequestInterrupts(tInterruptHandler handler, void *param=NULL); ///< Asynchronus handler version.
+ virtual void RequestInterrupts(); ///< Synchronus Wait version.
+protected:
+ AnalogTriggerOutput(AnalogTrigger *trigger, Type outputType);
+
+private:
+ AnalogTrigger *m_trigger;
+ Type m_outputType;
+};
+
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Base.h b/aos/externals/WPILib/WPILib/Base.h
new file mode 100644
index 0000000..ea2dc34
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Base.h
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef _BASE_H
+#define _BASE_H
+
+// A macro to disallow the copy constructor and operator= functions
+// This should be used in the private: declarations for a class
+#define DISALLOW_COPY_AND_ASSIGN(TypeName) \
+ TypeName(const TypeName&); \
+ void operator=(const TypeName&)
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Buttons/AnalogIOButton.cpp b/aos/externals/WPILib/WPILib/Buttons/AnalogIOButton.cpp
new file mode 100644
index 0000000..b2122ff
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/AnalogIOButton.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Buttons/AnalogIOButton.h"
+#include "DriverStation.h"
+
+const double AnalogIOButton::kThreshold = 0.5;
+
+AnalogIOButton::AnalogIOButton(int port) :
+ m_port(port)
+{
+}
+
+bool AnalogIOButton::Get()
+{
+ return DriverStation::GetInstance()->GetEnhancedIO().GetAnalogIn(m_port) < kThreshold;
+}
diff --git a/aos/externals/WPILib/WPILib/Buttons/AnalogIOButton.h b/aos/externals/WPILib/WPILib/Buttons/AnalogIOButton.h
new file mode 100644
index 0000000..f5ef54b
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/AnalogIOButton.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __ANALOG_IO_BUTTON_H__
+#define __ANALOG_IO_BUTTON_H__
+
+#include "Buttons/Button.h"
+
+class AnalogIOButton : public Button
+{
+public:
+ static const double kThreshold;
+
+ AnalogIOButton(int port);
+ virtual ~AnalogIOButton() {}
+ virtual bool Get();
+
+private:
+ int m_port;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Buttons/Button.cpp b/aos/externals/WPILib/WPILib/Buttons/Button.cpp
new file mode 100644
index 0000000..81671af
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/Button.cpp
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Buttons/Button.h"
+
+#include "Buttons/HeldButtonScheduler.h"
+#include "Buttons/PressedButtonScheduler.h"
+#include "Buttons/ReleasedButtonScheduler.h"
+#include "NetworkTables/NetworkTable.h"
+
+Button::Button() {
+ m_table = NULL;
+}
+
+bool Button::Grab()
+{
+ if (Get())
+ return true;
+ else if (m_table != NULL)
+ {
+ if (m_table->IsConnected())
+ return m_table->GetBoolean("pressed");
+ else
+ return false;
+ }
+ else
+ return false;
+}
+
+void Button::WhenPressed(Command *command)
+{
+ PressedButtonScheduler *pbs = new PressedButtonScheduler(Grab(), this, command);
+ pbs->Start();
+}
+
+void Button::WhileHeld(Command *command)
+{
+ HeldButtonScheduler *hbs = new HeldButtonScheduler(Grab(), this, command);
+ hbs->Start();
+}
+
+void Button::WhenReleased(Command *command)
+{
+ ReleasedButtonScheduler *rbs = new ReleasedButtonScheduler(Grab(), this, command);
+ rbs->Start();
+}
+
+NetworkTable* Button::GetTable()
+{
+ if (m_table == NULL)
+ {
+ m_table = new NetworkTable();
+ m_table->PutBoolean("pressed", Get());
+ }
+ return m_table;
+}
diff --git a/aos/externals/WPILib/WPILib/Buttons/Button.h b/aos/externals/WPILib/WPILib/Buttons/Button.h
new file mode 100644
index 0000000..da83339
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/Button.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __BUTTON_H__
+#define __BUTTON_H__
+
+#include "SmartDashboard/SmartDashboardData.h"
+
+class Command;
+
+class Button : public SmartDashboardData
+{
+public:
+ Button();
+ virtual ~Button() {}
+ bool Grab();
+ virtual bool Get() = 0;
+ void WhenPressed(Command *command);
+ void WhileHeld(Command *command);
+ void WhenReleased(Command *command);
+
+ virtual std::string GetType() {return "Button";}
+ virtual NetworkTable *GetTable();
+
+protected:
+ NetworkTable* m_table;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Buttons/ButtonScheduler.cpp b/aos/externals/WPILib/WPILib/Buttons/ButtonScheduler.cpp
new file mode 100644
index 0000000..c75e203
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/ButtonScheduler.cpp
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Buttons/ButtonScheduler.h"
+
+#include "Commands/Scheduler.h"
+#include "NetworkTables/NetworkTable.h"
+
+ButtonScheduler::ButtonScheduler(bool last, Button *button, Command *orders) :
+ m_pressedLast(last),
+ m_button(button),
+ m_command(orders)
+{
+}
+
+void ButtonScheduler::Start()
+{
+ Scheduler::GetInstance()->AddButton(this);
+}
diff --git a/aos/externals/WPILib/WPILib/Buttons/ButtonScheduler.h b/aos/externals/WPILib/WPILib/Buttons/ButtonScheduler.h
new file mode 100644
index 0000000..15e6fb9
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/ButtonScheduler.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __BUTTON_SCHEDULER_H__
+#define __BUTTON_SCHEDULER_H__
+
+class Button;
+class Command;
+
+class ButtonScheduler
+{
+public:
+ ButtonScheduler(bool last, Button *button, Command *orders);
+ virtual ~ButtonScheduler() {}
+ virtual void Execute() = 0;
+ void Start();
+
+protected:
+ bool m_pressedLast;
+ Button *m_button;
+ Command *m_command;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Buttons/DigitalIOButton.cpp b/aos/externals/WPILib/WPILib/Buttons/DigitalIOButton.cpp
new file mode 100644
index 0000000..8bb39be
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/DigitalIOButton.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Buttons/DigitalIOButton.h"
+#include "DriverStation.h"
+
+const bool DigitalIOButton::kActiveState = false;
+
+DigitalIOButton::DigitalIOButton(int port) :
+ m_port(port)
+{
+}
+
+bool DigitalIOButton::Get()
+{
+ return DriverStation::GetInstance()->GetEnhancedIO().GetDigital(m_port) == kActiveState;
+}
diff --git a/aos/externals/WPILib/WPILib/Buttons/DigitalIOButton.h b/aos/externals/WPILib/WPILib/Buttons/DigitalIOButton.h
new file mode 100644
index 0000000..6482c75
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/DigitalIOButton.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __DIGITAL_IO_BUTTON_H__
+#define __DIGITAL_IO_BUTTON_H__
+
+#include "Buttons/Button.h"
+
+class DigitalIOButton: public Button
+{
+public:
+ static const bool kActiveState;
+
+ DigitalIOButton(int port);
+ virtual ~DigitalIOButton() {}
+
+ virtual bool Get();
+
+private:
+ int m_port;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Buttons/HeldButtonScheduler.cpp b/aos/externals/WPILib/WPILib/Buttons/HeldButtonScheduler.cpp
new file mode 100644
index 0000000..f7b7a49
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/HeldButtonScheduler.cpp
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Buttons/HeldButtonScheduler.h"
+
+#include "Buttons/Button.h"
+#include "Commands/Command.h"
+
+HeldButtonScheduler::HeldButtonScheduler(bool last, Button *button, Command *orders) :
+ ButtonScheduler(last, button, orders)
+{
+}
+
+void HeldButtonScheduler::Execute()
+{
+ if (m_button->Grab())
+ {
+ m_pressedLast = true;
+ m_command->Start();
+ }
+ else
+ {
+ if (m_pressedLast)
+ {
+ m_pressedLast = false;
+ m_command->Cancel();
+ }
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/Buttons/HeldButtonScheduler.h b/aos/externals/WPILib/WPILib/Buttons/HeldButtonScheduler.h
new file mode 100644
index 0000000..3e50b97
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/HeldButtonScheduler.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __HELD_BUTTON_SCHEDULER_H__
+#define __HELD_BUTTON_SCHEDULER_H__
+
+#include "Buttons/ButtonScheduler.h"
+
+class Button;
+class Command;
+
+class HeldButtonScheduler : public ButtonScheduler
+{
+public:
+ HeldButtonScheduler(bool last, Button *button, Command *orders);
+ virtual ~HeldButtonScheduler() {}
+ virtual void Execute();
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Buttons/InternalButton.cpp b/aos/externals/WPILib/WPILib/Buttons/InternalButton.cpp
new file mode 100644
index 0000000..0bd322d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/InternalButton.cpp
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Buttons/InternalButton.h"
+
+InternalButton::InternalButton() :
+ m_pressed(false),
+ m_inverted(false)
+{
+}
+
+InternalButton::InternalButton(bool inverted) :
+ m_pressed(inverted),
+ m_inverted(inverted)
+{
+}
+
+void InternalButton::SetInverted(bool inverted)
+{
+ m_inverted = inverted;
+}
+
+void InternalButton::SetPressed(bool pressed)
+{
+ m_pressed = pressed;
+}
+
+bool InternalButton::Get()
+{
+ return m_pressed ^ m_inverted;
+}
diff --git a/aos/externals/WPILib/WPILib/Buttons/InternalButton.h b/aos/externals/WPILib/WPILib/Buttons/InternalButton.h
new file mode 100644
index 0000000..e61cf0a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/InternalButton.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __INTERNAL_BUTTON_H__
+#define __INTERNAL_BUTTON_H__
+
+#include "Buttons/Button.h"
+
+class InternalButton : public Button
+{
+public:
+ InternalButton();
+ InternalButton(bool inverted);
+ virtual ~InternalButton() {}
+
+ void SetInverted(bool inverted);
+ void SetPressed(bool pressed);
+
+ virtual bool Get();
+
+private:
+ bool m_pressed;
+ bool m_inverted;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Buttons/JoystickButton.cpp b/aos/externals/WPILib/WPILib/Buttons/JoystickButton.cpp
new file mode 100644
index 0000000..3dace65
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/JoystickButton.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Buttons/JoystickButton.h"
+
+JoystickButton::JoystickButton(GenericHID *joystick, int buttonNumber) :
+ m_joystick(joystick),
+ m_buttonNumber(buttonNumber)
+{
+}
+
+bool JoystickButton::Get()
+{
+ return m_joystick->GetRawButton(m_buttonNumber);
+}
diff --git a/aos/externals/WPILib/WPILib/Buttons/JoystickButton.h b/aos/externals/WPILib/WPILib/Buttons/JoystickButton.h
new file mode 100644
index 0000000..cb5f0c4
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/JoystickButton.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __JOYSTICK_BUTTON_H__
+#define __JOYSTICK_BUTTON_H__
+
+#include "GenericHID.h"
+#include "Buttons/Button.h"
+
+class JoystickButton : public Button
+{
+public:
+ JoystickButton(GenericHID *joystick, int buttonNumber);
+ virtual ~JoystickButton() {}
+
+ virtual bool Get();
+
+private:
+ GenericHID *m_joystick;
+ int m_buttonNumber;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Buttons/NetworkButton.cpp b/aos/externals/WPILib/WPILib/Buttons/NetworkButton.cpp
new file mode 100644
index 0000000..9fc3bba
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/NetworkButton.cpp
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Buttons/NetworkButton.h"
+
+#include "NetworkTables/NetworkTable.h"
+
+NetworkButton::NetworkButton(const char *tableName, const char *field) :
+ m_netTable(NetworkTable::GetTable(tableName)),
+ m_field(field)
+{
+}
+
+NetworkButton::NetworkButton(NetworkTable *table, const char *field) :
+ m_netTable(table),
+ m_field(field)
+{
+}
+
+bool NetworkButton::Get()
+{
+ if (m_netTable->IsConnected())
+ return m_netTable->GetBoolean(m_field.c_str());
+ else
+ return false;
+}
diff --git a/aos/externals/WPILib/WPILib/Buttons/NetworkButton.h b/aos/externals/WPILib/WPILib/Buttons/NetworkButton.h
new file mode 100644
index 0000000..40af41a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/NetworkButton.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __NETWORK_BUTTON_H__
+#define __NETWORK_BUTTON_H__
+
+#include "Buttons/Button.h"
+#include <string>
+
+class NetworkTable;
+
+class NetworkButton : public Button
+{
+public:
+ NetworkButton(const char *tableName, const char *field);
+ NetworkButton(NetworkTable* table, const char *field);
+ virtual ~NetworkButton() {}
+
+ virtual bool Get();
+
+private:
+ NetworkTable* m_netTable;
+ std::string m_field;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Buttons/PressedButtonScheduler.cpp b/aos/externals/WPILib/WPILib/Buttons/PressedButtonScheduler.cpp
new file mode 100644
index 0000000..d6a3451
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/PressedButtonScheduler.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Buttons/PressedButtonScheduler.h"
+
+#include "Buttons/Button.h"
+#include "Commands/Command.h"
+
+PressedButtonScheduler::PressedButtonScheduler(bool last, Button *button, Command *orders) :
+ ButtonScheduler(last, button, orders)
+{
+}
+
+void PressedButtonScheduler::Execute()
+{
+ if (m_button->Grab())
+ {
+ if (!m_pressedLast)
+ {
+ m_pressedLast = true;
+ m_command->Start();
+ }
+ }
+ else
+ {
+ m_pressedLast = false;
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/Buttons/PressedButtonScheduler.h b/aos/externals/WPILib/WPILib/Buttons/PressedButtonScheduler.h
new file mode 100644
index 0000000..e6ebc3a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/PressedButtonScheduler.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __PRESSED_BUTTON_SCHEDULER_H__
+#define __PRESSED_BUTTON_SCHEDULER_H__
+
+#include "Buttons/ButtonScheduler.h"
+
+class Button;
+class Command;
+
+class PressedButtonScheduler : public ButtonScheduler
+{
+public:
+ PressedButtonScheduler(bool last, Button *button, Command *orders);
+ virtual ~PressedButtonScheduler() {}
+ virtual void Execute();
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Buttons/ReleasedButtonScheduler.cpp b/aos/externals/WPILib/WPILib/Buttons/ReleasedButtonScheduler.cpp
new file mode 100644
index 0000000..a0f1bdc
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/ReleasedButtonScheduler.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Buttons/ReleasedButtonScheduler.h"
+
+#include "Buttons/Button.h"
+#include "Commands/Command.h"
+
+ReleasedButtonScheduler::ReleasedButtonScheduler(bool last, Button *button, Command *orders) :
+ ButtonScheduler(last, button, orders)
+{
+}
+
+void ReleasedButtonScheduler::Execute()
+{
+ if (m_button->Grab())
+ {
+ m_pressedLast = true;
+ }
+ else
+ {
+ if (m_pressedLast)
+ {
+ m_pressedLast = false;
+ m_command->Start();
+ }
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/Buttons/ReleasedButtonScheduler.h b/aos/externals/WPILib/WPILib/Buttons/ReleasedButtonScheduler.h
new file mode 100644
index 0000000..dc2eb78
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Buttons/ReleasedButtonScheduler.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __RELEASED_BUTTON_SCHEDULER_H__
+#define __RELEASED_BUTTON_SCHEDULER_H__
+
+#include "Buttons/ButtonScheduler.h"
+
+class Button;
+class Command;
+
+class ReleasedButtonScheduler : public ButtonScheduler
+{
+public:
+ ReleasedButtonScheduler(bool last, Button *button, Command *orders);
+ virtual ~ReleasedButtonScheduler() {}
+ virtual void Execute();
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/CAN/JaguarCANDriver.h b/aos/externals/WPILib/WPILib/CAN/JaguarCANDriver.h
new file mode 100644
index 0000000..35c82a5
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CAN/JaguarCANDriver.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2009. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+// JaguarCANDriver.h
+//
+// Defines the API for building a CAN Interface Plugin to support
+// PWM-cable-free CAN motor control on FRC robots. This allows you
+// to connect any CAN interface to the secure Jaguar CAN driver.
+//
+
+#ifndef __JaguarCANDriver_h__
+#define __JaguarCANDriver_h__
+
+#include <VxWorks.h>
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+ void FRC_NetworkCommunication_JaguarCANDriver_sendMessage(UINT32 messageID, const UINT8 *data, UINT8 dataSize, INT32 *status);
+ void FRC_NetworkCommunication_JaguarCANDriver_receiveMessage(UINT32 *messageID, UINT8 *data, UINT8 *dataSize, UINT32 timeoutMs, INT32 *status);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // __JaguarCANDriver_h__
diff --git a/aos/externals/WPILib/WPILib/CAN/can_proto.h b/aos/externals/WPILib/WPILib/CAN/can_proto.h
new file mode 100644
index 0000000..5113b02
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CAN/can_proto.h
@@ -0,0 +1,428 @@
+//*****************************************************************************
+//
+// can_proto.h - Definitions for the CAN protocol used to communicate with the
+// BDC motor controller.
+//
+// Copyright (c) 2008 Texas Instruments Incorporated. All rights reserved.
+// TI Information - Selective Disclosure
+//
+//*****************************************************************************
+
+#ifndef __CAN_PROTO_H__
+#define __CAN_PROTO_H__
+
+//*****************************************************************************
+//
+// The masks of the fields that are used in the message identifier.
+//
+//*****************************************************************************
+#define CAN_MSGID_FULL_M 0x1fffffff
+#define CAN_MSGID_DEVNO_M 0x0000003f
+#define CAN_MSGID_API_M 0x0000ffc0
+#define CAN_MSGID_MFR_M 0x00ff0000
+#define CAN_MSGID_DTYPE_M 0x1f000000
+#define CAN_MSGID_DEVNO_S 0
+#define CAN_MSGID_API_S 6
+#define CAN_MSGID_MFR_S 16
+#define CAN_MSGID_DTYPE_S 24
+
+//*****************************************************************************
+//
+// The Reserved device number values in the Message Id.
+//
+//*****************************************************************************
+#define CAN_MSGID_DEVNO_BCAST 0x00000000
+
+//*****************************************************************************
+//
+// The Reserved system control API numbers in the Message Id.
+//
+//*****************************************************************************
+#define CAN_MSGID_API_SYSHALT 0x00000000
+#define CAN_MSGID_API_SYSRST 0x00000040
+#define CAN_MSGID_API_DEVASSIGN 0x00000080
+#define CAN_MSGID_API_DEVQUERY 0x000000c0
+#define CAN_MSGID_API_HEARTBEAT 0x00000140
+#define CAN_MSGID_API_SYNC 0x00000180
+#define CAN_MSGID_API_UPDATE 0x000001c0
+#define CAN_MSGID_API_FIRMVER 0x00000200
+#define CAN_MSGID_API_ENUMERATE 0x00000240
+#define CAN_MSGID_API_SYSRESUME 0x00000280
+
+//*****************************************************************************
+//
+// The 32 bit values associated with the CAN_MSGID_API_STATUS request.
+//
+//*****************************************************************************
+#define CAN_STATUS_CODE_M 0x0000ffff
+#define CAN_STATUS_MFG_M 0x00ff0000
+#define CAN_STATUS_DTYPE_M 0x1f000000
+#define CAN_STATUS_CODE_S 0
+#define CAN_STATUS_MFG_S 16
+#define CAN_STATUS_DTYPE_S 24
+
+//*****************************************************************************
+//
+// The Reserved manufacturer identifiers in the Message Id.
+//
+//*****************************************************************************
+#define CAN_MSGID_MFR_NI 0x00010000
+#define CAN_MSGID_MFR_LM 0x00020000
+#define CAN_MSGID_MFR_DEKA 0x00030000
+
+//*****************************************************************************
+//
+// The Reserved device type identifiers in the Message Id.
+//
+//*****************************************************************************
+#define CAN_MSGID_DTYPE_BCAST 0x00000000
+#define CAN_MSGID_DTYPE_ROBOT 0x01000000
+#define CAN_MSGID_DTYPE_MOTOR 0x02000000
+#define CAN_MSGID_DTYPE_RELAY 0x03000000
+#define CAN_MSGID_DTYPE_GYRO 0x04000000
+#define CAN_MSGID_DTYPE_ACCEL 0x05000000
+#define CAN_MSGID_DTYPE_USONIC 0x06000000
+#define CAN_MSGID_DTYPE_GEART 0x07000000
+#define CAN_MSGID_DTYPE_UPDATE 0x1f000000
+
+//*****************************************************************************
+//
+// LM Motor Control API Classes API Class and ID masks.
+//
+//*****************************************************************************
+#define CAN_MSGID_API_CLASS_M 0x0000fc00
+#define CAN_MSGID_API_ID_M 0x000003c0
+
+//*****************************************************************************
+//
+// LM Motor Control API Classes in the Message Id for non-broadcast.
+// These are the upper 6 bits of the API field, the lower 4 bits determine
+// the APIId.
+//
+//*****************************************************************************
+#define CAN_API_MC_VOLTAGE 0x00000000
+#define CAN_API_MC_SPD 0x00000400
+#define CAN_API_MC_VCOMP 0x00000800
+#define CAN_API_MC_POS 0x00000c00
+#define CAN_API_MC_ICTRL 0x00001000
+#define CAN_API_MC_STATUS 0x00001400
+#define CAN_API_MC_PSTAT 0x00001800
+#define CAN_API_MC_CFG 0x00001c00
+#define CAN_API_MC_ACK 0x00002000
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Control Voltage API definitions.
+//
+//*****************************************************************************
+#define LM_API_VOLT (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
+ CAN_API_MC_VOLTAGE)
+#define LM_API_VOLT_EN (LM_API_VOLT | (0 << CAN_MSGID_API_S))
+#define LM_API_VOLT_DIS (LM_API_VOLT | (1 << CAN_MSGID_API_S))
+#define LM_API_VOLT_SET (LM_API_VOLT | (2 << CAN_MSGID_API_S))
+#define LM_API_VOLT_SET_RAMP (LM_API_VOLT | (3 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_VOLT_T_EN (LM_API_VOLT | (4 << CAN_MSGID_API_S))
+#define LM_API_VOLT_T_SET (LM_API_VOLT | (5 << CAN_MSGID_API_S))
+#define LM_API_VOLT_T_SET_NO_ACK \
+ (LM_API_VOLT | (7 << CAN_MSGID_API_S))
+//##### FIRST END #####
+#define LM_API_VOLT_SET_NO_ACK (LM_API_VOLT | (8 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Control API definitions for LM_API_VOLT_SET_RAMP.
+//
+//*****************************************************************************
+#define LM_API_VOLT_RAMP_DIS 0
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Control API definitions for CAN_MSGID_API_SYNC.
+//
+//*****************************************************************************
+#define LM_API_SYNC_PEND_NOW 0
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Speed Control API definitions.
+//
+//*****************************************************************************
+#define LM_API_SPD (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
+ CAN_API_MC_SPD)
+#define LM_API_SPD_EN (LM_API_SPD | (0 << CAN_MSGID_API_S))
+#define LM_API_SPD_DIS (LM_API_SPD | (1 << CAN_MSGID_API_S))
+#define LM_API_SPD_SET (LM_API_SPD | (2 << CAN_MSGID_API_S))
+#define LM_API_SPD_PC (LM_API_SPD | (3 << CAN_MSGID_API_S))
+#define LM_API_SPD_IC (LM_API_SPD | (4 << CAN_MSGID_API_S))
+#define LM_API_SPD_DC (LM_API_SPD | (5 << CAN_MSGID_API_S))
+#define LM_API_SPD_REF (LM_API_SPD | (6 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_SPD_T_EN (LM_API_SPD | (7 << CAN_MSGID_API_S))
+#define LM_API_SPD_T_SET (LM_API_SPD | (8 << CAN_MSGID_API_S))
+#define LM_API_SPD_T_SET_NO_ACK (LM_API_SPD | (10 << CAN_MSGID_API_S))
+//##### FIRST END #####
+#define LM_API_SPD_SET_NO_ACK (LM_API_SPD | (11 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris Motor Control Voltage Compensation Control API definitions.
+//
+//*****************************************************************************
+#define LM_API_VCOMP (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
+ CAN_API_MC_VCOMP)
+#define LM_API_VCOMP_EN (LM_API_VCOMP | (0 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_DIS (LM_API_VCOMP | (1 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_SET (LM_API_VCOMP | (2 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_IN_RAMP (LM_API_VCOMP | (3 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_COMP_RAMP (LM_API_VCOMP | (4 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_VCOMP_T_EN (LM_API_VCOMP | (5 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_T_SET (LM_API_VCOMP | (6 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_T_SET_NO_ACK \
+ (LM_API_VCOMP | (8 << CAN_MSGID_API_S))
+//##### FIRST END #####
+#define LM_API_VCOMP_SET_NO_ACK (LM_API_VCOMP | (9 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Position Control API definitions.
+//
+//*****************************************************************************
+#define LM_API_POS (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
+ CAN_API_MC_POS)
+#define LM_API_POS_EN (LM_API_POS | (0 << CAN_MSGID_API_S))
+#define LM_API_POS_DIS (LM_API_POS | (1 << CAN_MSGID_API_S))
+#define LM_API_POS_SET (LM_API_POS | (2 << CAN_MSGID_API_S))
+#define LM_API_POS_PC (LM_API_POS | (3 << CAN_MSGID_API_S))
+#define LM_API_POS_IC (LM_API_POS | (4 << CAN_MSGID_API_S))
+#define LM_API_POS_DC (LM_API_POS | (5 << CAN_MSGID_API_S))
+#define LM_API_POS_REF (LM_API_POS | (6 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_POS_T_EN (LM_API_POS | (7 << CAN_MSGID_API_S))
+#define LM_API_POS_T_SET (LM_API_POS | (8 << CAN_MSGID_API_S))
+#define LM_API_POS_T_SET_NO_ACK (LM_API_POS | (10 << CAN_MSGID_API_S))
+//##### FIRST END #####
+#define LM_API_POS_SET_NO_ACK (LM_API_POS | (11 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Current Control API definitions.
+//
+//*****************************************************************************
+#define LM_API_ICTRL (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
+ CAN_API_MC_ICTRL)
+#define LM_API_ICTRL_EN (LM_API_ICTRL | (0 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_DIS (LM_API_ICTRL | (1 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_SET (LM_API_ICTRL | (2 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_PC (LM_API_ICTRL | (3 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_IC (LM_API_ICTRL | (4 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_DC (LM_API_ICTRL | (5 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_ICTRL_T_EN (LM_API_ICTRL | (6 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_T_SET (LM_API_ICTRL | (7 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_T_SET_NO_ACK \
+ (LM_API_ICTRL | (9 << CAN_MSGID_API_S))
+//##### FIRST END #####
+#define LM_API_ICTRL_SET_NO_ACK (LM_API_ICTRL | (10 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Firmware Update API definitions.
+//
+//*****************************************************************************
+#define LM_API_UPD (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_UPDATE)
+#define LM_API_UPD_PING (LM_API_UPD | (0 << CAN_MSGID_API_S))
+#define LM_API_UPD_DOWNLOAD (LM_API_UPD | (1 << CAN_MSGID_API_S))
+#define LM_API_UPD_SEND_DATA (LM_API_UPD | (2 << CAN_MSGID_API_S))
+#define LM_API_UPD_RESET (LM_API_UPD | (3 << CAN_MSGID_API_S))
+#define LM_API_UPD_ACK (LM_API_UPD | (4 << CAN_MSGID_API_S))
+#define LM_API_HWVER (LM_API_UPD | (5 << CAN_MSGID_API_S))
+#define LM_API_UPD_REQUEST (LM_API_UPD | (6 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_UNTRUST_EN (LM_API_UPD | (11 << CAN_MSGID_API_S))
+#define LM_API_TRUST_EN (LM_API_UPD | (12 << CAN_MSGID_API_S))
+#define LM_API_TRUST_HEARTBEAT (LM_API_UPD | (13 << CAN_MSGID_API_S))
+//##### FIRST END #####
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Status API definitions.
+//
+//*****************************************************************************
+#define LM_API_STATUS (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
+ CAN_API_MC_STATUS)
+#define LM_API_STATUS_VOLTOUT (LM_API_STATUS | (0 << CAN_MSGID_API_S))
+#define LM_API_STATUS_VOLTBUS (LM_API_STATUS | (1 << CAN_MSGID_API_S))
+#define LM_API_STATUS_CURRENT (LM_API_STATUS | (2 << CAN_MSGID_API_S))
+#define LM_API_STATUS_TEMP (LM_API_STATUS | (3 << CAN_MSGID_API_S))
+#define LM_API_STATUS_POS (LM_API_STATUS | (4 << CAN_MSGID_API_S))
+#define LM_API_STATUS_SPD (LM_API_STATUS | (5 << CAN_MSGID_API_S))
+#define LM_API_STATUS_LIMIT (LM_API_STATUS | (6 << CAN_MSGID_API_S))
+#define LM_API_STATUS_FAULT (LM_API_STATUS | (7 << CAN_MSGID_API_S))
+#define LM_API_STATUS_POWER (LM_API_STATUS | (8 << CAN_MSGID_API_S))
+#define LM_API_STATUS_CMODE (LM_API_STATUS | (9 << CAN_MSGID_API_S))
+#define LM_API_STATUS_VOUT (LM_API_STATUS | (10 << CAN_MSGID_API_S))
+#define LM_API_STATUS_STKY_FLT (LM_API_STATUS | (11 << CAN_MSGID_API_S))
+#define LM_API_STATUS_FLT_COUNT (LM_API_STATUS | (12 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// These definitions are used with the byte that is returned from
+// the status request for LM_API_STATUS_LIMIT.
+//
+//*****************************************************************************
+#define LM_STATUS_LIMIT_FWD 0x01
+#define LM_STATUS_LIMIT_REV 0x02
+#define LM_STATUS_LIMIT_SFWD 0x04
+#define LM_STATUS_LIMIT_SREV 0x08
+#define LM_STATUS_LIMIT_STKY_FWD \
+ 0x10
+#define LM_STATUS_LIMIT_STKY_REV \
+ 0x20
+#define LM_STATUS_LIMIT_STKY_SFWD \
+ 0x40
+#define LM_STATUS_LIMIT_STKY_SREV \
+ 0x80
+
+//*****************************************************************************
+//
+// LM Motor Control status codes returned due to the CAN_STATUS_CODE_M field.
+//
+//*****************************************************************************
+#define LM_STATUS_FAULT_ILIMIT 0x01
+#define LM_STATUS_FAULT_TLIMIT 0x02
+#define LM_STATUS_FAULT_VLIMIT 0x04
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Configuration API definitions.
+//
+//*****************************************************************************
+#define LM_API_CFG (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
+ CAN_API_MC_CFG)
+#define LM_API_CFG_NUM_BRUSHES (LM_API_CFG | (0 << CAN_MSGID_API_S))
+#define LM_API_CFG_ENC_LINES (LM_API_CFG | (1 << CAN_MSGID_API_S))
+#define LM_API_CFG_POT_TURNS (LM_API_CFG | (2 << CAN_MSGID_API_S))
+#define LM_API_CFG_BRAKE_COAST (LM_API_CFG | (3 << CAN_MSGID_API_S))
+#define LM_API_CFG_LIMIT_MODE (LM_API_CFG | (4 << CAN_MSGID_API_S))
+#define LM_API_CFG_LIMIT_FWD (LM_API_CFG | (5 << CAN_MSGID_API_S))
+#define LM_API_CFG_LIMIT_REV (LM_API_CFG | (6 << CAN_MSGID_API_S))
+#define LM_API_CFG_MAX_VOUT (LM_API_CFG | (7 << CAN_MSGID_API_S))
+#define LM_API_CFG_FAULT_TIME (LM_API_CFG | (8 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris ACK API definition.
+//
+//*****************************************************************************
+#define LM_API_ACK (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
+ CAN_API_MC_ACK)
+
+//*****************************************************************************
+//
+// The 8 bit values that can be returned by a call to LM_API_STATUS_HWVER.
+//
+//*****************************************************************************
+#define LM_HWVER_UNKNOWN 0x00
+#define LM_HWVER_JAG_1_0 0x01
+#define LM_HWVER_JAG_2_0 0x02
+
+//*****************************************************************************
+//
+// The 8 bit values that can be returned by a call to LM_API_STATUS_CMODE.
+//
+//*****************************************************************************
+#define LM_STATUS_CMODE_VOLT 0x00
+#define LM_STATUS_CMODE_CURRENT 0x01
+#define LM_STATUS_CMODE_SPEED 0x02
+#define LM_STATUS_CMODE_POS 0x03
+#define LM_STATUS_CMODE_VCOMP 0x04
+
+//*****************************************************************************
+//
+// The values that can specified as the position or speed reference. Not all
+// values are valid for each reference; if an invalid reference is set, then
+// none will be selected.
+//
+//*****************************************************************************
+#define LM_REF_ENCODER 0x00
+#define LM_REF_POT 0x01
+#define LM_REF_INV_ENCODER 0x02
+#define LM_REF_QUAD_ENCODER 0x03
+#define LM_REF_NONE 0xff
+
+//*****************************************************************************
+//
+// The flags that are used to indicate the currently active fault sources.
+//
+//*****************************************************************************
+#define LM_FAULT_CURRENT 0x01
+#define LM_FAULT_TEMP 0x02
+#define LM_FAULT_VBUS 0x04
+#define LM_FAULT_GATE_DRIVE 0x08
+#define LM_FAULT_COMM 0x10
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Periodic Status API definitions.
+//
+//*****************************************************************************
+#define LM_API_PSTAT (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
+ CAN_API_MC_PSTAT)
+#define LM_API_PSTAT_PER_EN_S0 (LM_API_PSTAT | (0 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_PER_EN_S1 (LM_API_PSTAT | (1 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_PER_EN_S2 (LM_API_PSTAT | (2 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_PER_EN_S3 (LM_API_PSTAT | (3 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_CFG_S0 (LM_API_PSTAT | (4 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_CFG_S1 (LM_API_PSTAT | (5 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_CFG_S2 (LM_API_PSTAT | (6 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_CFG_S3 (LM_API_PSTAT | (7 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_DATA_S0 (LM_API_PSTAT | (8 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_DATA_S1 (LM_API_PSTAT | (9 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_DATA_S2 (LM_API_PSTAT | (10 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_DATA_S3 (LM_API_PSTAT | (11 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The values that can be used to configure the data the Periodic Status
+// Message bytes. Bytes of a multi-byte data values are encoded as
+// little-endian, therefore B0 is the least significant byte.
+//
+//*****************************************************************************
+#define LM_PSTAT_END 0
+#define LM_PSTAT_VOLTOUT_B0 1
+#define LM_PSTAT_VOLTOUT_B1 2
+#define LM_PSTAT_VOLTBUS_B0 3
+#define LM_PSTAT_VOLTBUS_B1 4
+#define LM_PSTAT_CURRENT_B0 5
+#define LM_PSTAT_CURRENT_B1 6
+#define LM_PSTAT_TEMP_B0 7
+#define LM_PSTAT_TEMP_B1 8
+#define LM_PSTAT_POS_B0 9
+#define LM_PSTAT_POS_B1 10
+#define LM_PSTAT_POS_B2 11
+#define LM_PSTAT_POS_B3 12
+#define LM_PSTAT_SPD_B0 13
+#define LM_PSTAT_SPD_B1 14
+#define LM_PSTAT_SPD_B2 15
+#define LM_PSTAT_SPD_B3 16
+#define LM_PSTAT_LIMIT_NCLR 17
+#define LM_PSTAT_LIMIT_CLR 18
+#define LM_PSTAT_FAULT 19
+#define LM_PSTAT_STKY_FLT_NCLR 20
+#define LM_PSTAT_STKY_FLT_CLR 21
+#define LM_PSTAT_VOUT_B0 22
+#define LM_PSTAT_VOUT_B1 23
+#define LM_PSTAT_FLT_COUNT_CURRENT \
+ 24
+#define LM_PSTAT_FLT_COUNT_TEMP 25
+#define LM_PSTAT_FLT_COUNT_VOLTBUS \
+ 26
+#define LM_PSTAT_FLT_COUNT_GATE 27
+#define LM_PSTAT_FLT_COUNT_COMM 28
+#define LM_PSTAT_CANSTS 29
+#define LM_PSTAT_CANERR_B0 30
+#define LM_PSTAT_CANERR_B1 31
+
+#endif // __CAN_PROTO_H__
diff --git a/aos/externals/WPILib/WPILib/CANJaguar.cpp b/aos/externals/WPILib/WPILib/CANJaguar.cpp
new file mode 100644
index 0000000..4261d98
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CANJaguar.cpp
@@ -0,0 +1,1237 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2009. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "CANJaguar.h"
+#define tNIRIO_i32 int
+#include "ChipObject/NiFpga.h"
+#include "CAN/JaguarCANDriver.h"
+#include "CAN/can_proto.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+#include <stdio.h>
+
+#define swap16(x) ( (((x)>>8) &0x00FF) \
+ | (((x)<<8) &0xFF00) )
+#define swap32(x) ( (((x)>>24)&0x000000FF) \
+ | (((x)>>8) &0x0000FF00) \
+ | (((x)<<8) &0x00FF0000) \
+ | (((x)<<24)&0xFF000000) )
+
+#define kFullMessageIDMask (CAN_MSGID_API_M | CAN_MSGID_MFR_M | CAN_MSGID_DTYPE_M)
+
+const INT32 CANJaguar::kControllerRate;
+const double CANJaguar::kApproxBusVoltage;
+
+/**
+ * Common initialization code called by all constructors.
+ */
+void CANJaguar::InitCANJaguar()
+{
+ m_transactionSemaphore = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+ if (m_deviceNumber < 1 || m_deviceNumber > 63)
+ {
+ char buf[256];
+ snprintf(buf, 256, "device number \"%d\" must be between 1 and 63", m_deviceNumber);
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, buf);
+ return;
+ }
+ UINT32 fwVer = GetFirmwareVersion();
+ if (StatusIsFatal())
+ return;
+ // 3330 was the first shipping RDK firmware version for the Jaguar
+ if (fwVer >= 3330 || fwVer < 92)
+ {
+ char buf[256];
+ if (fwVer < 3330)
+ {
+ snprintf(buf, 256, "Jag #%d firmware (%d) is too old (must be at least version 92 of the FIRST approved firmware)", m_deviceNumber, fwVer);
+ }
+ else
+ {
+ snprintf(buf, 256, "Jag #%d firmware (%d) is not FIRST approved (must be at least version 92 of the FIRST approved firmware)", m_deviceNumber, fwVer);
+ }
+ wpi_setWPIErrorWithContext(JaguarVersionError, buf);
+ return;
+ }
+ switch (m_controlMode)
+ {
+ case kPercentVbus:
+ case kVoltage:
+ // No additional configuration required... start enabled.
+ EnableControl();
+ break;
+ default:
+ break;
+ }
+ m_safetyHelper = new MotorSafetyHelper(this);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_CANJaguar, m_deviceNumber, m_controlMode);
+}
+
+/**
+ * Constructor
+ *
+ * @param deviceNumber The the address of the Jaguar on the CAN bus.
+ */
+CANJaguar::CANJaguar(UINT8 deviceNumber, ControlMode controlMode)
+ : m_deviceNumber (deviceNumber)
+ , m_controlMode (controlMode)
+ , m_transactionSemaphore (NULL)
+ , m_maxOutputVoltage (kApproxBusVoltage)
+ , m_safetyHelper (NULL)
+{
+ InitCANJaguar();
+}
+
+CANJaguar::~CANJaguar()
+{
+ delete m_safetyHelper;
+ m_safetyHelper = NULL;
+ semDelete(m_transactionSemaphore);
+ m_transactionSemaphore = NULL;
+}
+
+/**
+ * Set the output set-point value.
+ *
+ * The scale and the units depend on the mode the Jaguar is in.
+ * In PercentVbus Mode, the outputValue is from -1.0 to 1.0 (same as PWM Jaguar).
+ * In Voltage Mode, the outputValue is in Volts.
+ * In Current Mode, the outputValue is in Amps.
+ * In Speed Mode, the outputValue is in Rotations/Minute.
+ * In Position Mode, the outputValue is in Rotations.
+ *
+ * @param outputValue The set-point to sent to the motor controller.
+ * @param syncGroup The update group to add this Set() to, pending UpdateSyncGroup(). If 0, update immediately.
+ */
+void CANJaguar::Set(float outputValue, UINT8 syncGroup)
+{
+ UINT32 messageID;
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ if (m_safetyHelper && !m_safetyHelper->IsAlive())
+ {
+ EnableControl();
+ }
+
+ switch(m_controlMode)
+ {
+ case kPercentVbus:
+ {
+ messageID = LM_API_VOLT_T_SET;
+ if (outputValue > 1.0) outputValue = 1.0;
+ if (outputValue < -1.0) outputValue = -1.0;
+ dataSize = packPercentage(dataBuffer, outputValue);
+ }
+ break;
+ case kSpeed:
+ {
+ messageID = LM_API_SPD_T_SET;
+ dataSize = packFXP16_16(dataBuffer, outputValue);
+ }
+ break;
+ case kPosition:
+ {
+ messageID = LM_API_POS_T_SET;
+ dataSize = packFXP16_16(dataBuffer, outputValue);
+ }
+ break;
+ case kCurrent:
+ {
+ messageID = LM_API_ICTRL_T_SET;
+ dataSize = packFXP8_8(dataBuffer, outputValue);
+ }
+ break;
+ case kVoltage:
+ {
+ messageID = LM_API_VCOMP_T_SET;
+ dataSize = packFXP8_8(dataBuffer, outputValue);
+ }
+ break;
+ default:
+ return;
+ }
+ if (syncGroup != 0)
+ {
+ dataBuffer[dataSize] = syncGroup;
+ dataSize++;
+ }
+ setTransaction(messageID, dataBuffer, dataSize);
+ if (m_safetyHelper) m_safetyHelper->Feed();
+}
+
+/**
+ * Get the recently set outputValue setpoint.
+ *
+ * The scale and the units depend on the mode the Jaguar is in.
+ * In PercentVbus Mode, the outputValue is from -1.0 to 1.0 (same as PWM Jaguar).
+ * In Voltage Mode, the outputValue is in Volts.
+ * In Current Mode, the outputValue is in Amps.
+ * In Speed Mode, the outputValue is in Rotations/Minute.
+ * In Position Mode, the outputValue is in Rotations.
+ *
+ * @return The most recently set outputValue setpoint.
+ */
+float CANJaguar::Get()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ switch(m_controlMode)
+ {
+ case kPercentVbus:
+ getTransaction(LM_API_VOLT_SET, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT16))
+ {
+ return unpackPercentage(dataBuffer);
+ }
+ break;
+ case kSpeed:
+ getTransaction(LM_API_SPD_SET, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ break;
+ case kPosition:
+ getTransaction(LM_API_POS_SET, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ break;
+ case kCurrent:
+ getTransaction(LM_API_ICTRL_SET, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT16))
+ {
+ return unpackFXP8_8(dataBuffer);
+ }
+ break;
+ case kVoltage:
+ getTransaction(LM_API_VCOMP_SET, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT16))
+ {
+ return unpackFXP8_8(dataBuffer);
+ }
+ break;
+ }
+ return 0.0;
+}
+
+/**
+ * Common interface for disabling a motor.
+ *
+ * @deprecated Call DisableControl instead.
+ */
+void CANJaguar::Disable()
+{
+ DisableControl();
+}
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @deprecated Call Set instead.
+ *
+ * @param output Write out the PercentVbus value as was computed by the PIDController
+ */
+void CANJaguar::PIDWrite(float output)
+{
+ if (m_controlMode == kPercentVbus)
+ {
+ Set(output);
+ }
+ else
+ {
+ wpi_setWPIErrorWithContext(IncompatibleMode, "PID only supported in PercentVbus mode");
+ }
+}
+
+UINT8 CANJaguar::packPercentage(UINT8 *buffer, double value)
+{
+ INT16 intValue = (INT16)(value * 32767.0);
+ *((INT16*)buffer) = swap16(intValue);
+ return sizeof(INT16);
+}
+
+UINT8 CANJaguar::packFXP8_8(UINT8 *buffer, double value)
+{
+ INT16 intValue = (INT16)(value * 256.0);
+ *((INT16*)buffer) = swap16(intValue);
+ return sizeof(INT16);
+}
+
+UINT8 CANJaguar::packFXP16_16(UINT8 *buffer, double value)
+{
+ INT32 intValue = (INT32)(value * 65536.0);
+ *((INT32*)buffer) = swap32(intValue);
+ return sizeof(INT32);
+}
+
+UINT8 CANJaguar::packINT16(UINT8 *buffer, INT16 value)
+{
+ *((INT16*)buffer) = swap16(value);
+ return sizeof(INT16);
+}
+
+UINT8 CANJaguar::packINT32(UINT8 *buffer, INT32 value)
+{
+ *((INT32*)buffer) = swap32(value);
+ return sizeof(INT32);
+}
+
+double CANJaguar::unpackPercentage(UINT8 *buffer)
+{
+ INT16 value = *((INT16*)buffer);
+ value = swap16(value);
+ return value / 32767.0;
+}
+
+double CANJaguar::unpackFXP8_8(UINT8 *buffer)
+{
+ INT16 value = *((INT16*)buffer);
+ value = swap16(value);
+ return value / 256.0;
+}
+
+double CANJaguar::unpackFXP16_16(UINT8 *buffer)
+{
+ INT32 value = *((INT32*)buffer);
+ value = swap32(value);
+ return value / 65536.0;
+}
+
+INT16 CANJaguar::unpackINT16(UINT8 *buffer)
+{
+ INT16 value = *((INT16*)buffer);
+ return swap16(value);
+}
+
+INT32 CANJaguar::unpackINT32(UINT8 *buffer)
+{
+ INT32 value = *((INT32*)buffer);
+ return swap32(value);
+}
+
+/**
+ * Send a message on the CAN bus through the CAN driver in FRC_NetworkCommunication
+ *
+ * Trusted messages require a 2-byte token at the beginning of the data payload.
+ * If the message being sent is trusted, make space for the token.
+ *
+ * @param messageID The messageID to be used on the CAN bus
+ * @param data The up to 8 bytes of data to be sent with the message
+ * @param dataSize Specify how much of the data in "data" to send
+ * @return Status of send call
+ */
+INT32 CANJaguar::sendMessage(UINT32 messageID, const UINT8 *data, UINT8 dataSize)
+{
+ static const UINT32 kTrustedMessages[] = {
+ LM_API_VOLT_T_EN, LM_API_VOLT_T_SET, LM_API_SPD_T_EN, LM_API_SPD_T_SET,
+ LM_API_VCOMP_T_EN, LM_API_VCOMP_T_SET, LM_API_POS_T_EN, LM_API_POS_T_SET,
+ LM_API_ICTRL_T_EN, LM_API_ICTRL_T_SET};
+ INT32 status=0;
+
+ for (UINT8 i=0; i<(sizeof(kTrustedMessages)/sizeof(kTrustedMessages[0])); i++)
+ {
+ if ((kFullMessageIDMask & messageID) == kTrustedMessages[i])
+ {
+ UINT8 dataBuffer[8];
+ dataBuffer[0] = 0;
+ dataBuffer[1] = 0;
+ // Make sure the data will still fit after adjusting for the token.
+ if (dataSize > 6)
+ {
+ // TODO: I would rather this not have to set the global error
+ wpi_setGlobalWPIErrorWithContext(ParameterOutOfRange, "dataSize > 6");
+ return 0;
+ }
+ for (UINT8 j=0; j < dataSize; j++)
+ {
+ dataBuffer[j + 2] = data[j];
+ }
+ FRC_NetworkCommunication_JaguarCANDriver_sendMessage(messageID, dataBuffer, dataSize + 2, &status);
+ return status;
+ }
+ }
+ FRC_NetworkCommunication_JaguarCANDriver_sendMessage(messageID, data, dataSize, &status);
+ return status;
+}
+
+/**
+ * Receive a message from the CAN bus through the CAN driver in FRC_NetworkCommunication
+ *
+ * @param messageID The messageID to read from the CAN bus
+ * @param data The up to 8 bytes of data that was received with the message
+ * @param dataSize Indicates how much data was received
+ * @param timeout Specify how long to wait for a message (in seconds)
+ * @return Status of receive call
+ */
+INT32 CANJaguar::receiveMessage(UINT32 *messageID, UINT8 *data, UINT8 *dataSize, float timeout)
+{
+ INT32 status = 0;
+ FRC_NetworkCommunication_JaguarCANDriver_receiveMessage(messageID, data, dataSize,
+ (UINT32)(timeout * 1000), &status);
+ return status;
+}
+
+/**
+ * Execute a transaction with a Jaguar that sets some property.
+ *
+ * Jaguar always acks when it receives a message. If we don't wait for an ack,
+ * the message object in the Jaguar could get overwritten before it is handled.
+ *
+ * @param messageID The messageID to be used on the CAN bus (device number is added internally)
+ * @param data The up to 8 bytes of data to be sent with the message
+ * @param dataSize Specify how much of the data in "data" to send
+ */
+void CANJaguar::setTransaction(UINT32 messageID, const UINT8 *data, UINT8 dataSize)
+{
+ UINT32 ackMessageID = LM_API_ACK | m_deviceNumber;
+ INT32 localStatus = 0;
+
+ // If there was an error on this object and it wasn't a timeout, refuse to talk to the device
+ // Call ClearError() on the object to try again
+ if (StatusIsFatal() && GetError().GetCode() != -44087)
+ return;
+
+ // Make sure we don't have more than one transaction with the same Jaguar outstanding.
+ semTake(m_transactionSemaphore, WAIT_FOREVER);
+
+ // Throw away any stale acks.
+ receiveMessage(&ackMessageID, NULL, 0, 0.0f);
+ // Send the message with the data.
+ localStatus = sendMessage(messageID | m_deviceNumber, data, dataSize);
+ wpi_setErrorWithContext(localStatus, "sendMessage");
+ // Wait for an ack.
+ localStatus = receiveMessage(&ackMessageID, NULL, 0);
+ wpi_setErrorWithContext(localStatus, "receiveMessage");
+
+ // Transaction complete.
+ semGive(m_transactionSemaphore);
+}
+
+/**
+ * Execute a transaction with a Jaguar that gets some property.
+ *
+ * Jaguar always generates a message with the same message ID when replying.
+ *
+ * @param messageID The messageID to read from the CAN bus (device number is added internally)
+ * @param data The up to 8 bytes of data that was received with the message
+ * @param dataSize Indicates how much data was received
+ */
+void CANJaguar::getTransaction(UINT32 messageID, UINT8 *data, UINT8 *dataSize)
+{
+ UINT32 targetedMessageID = messageID | m_deviceNumber;
+ INT32 localStatus = 0;
+
+ // If there was an error on this object and it wasn't a timeout, refuse to talk to the device
+ // Call ClearError() on the object to try again
+ if (StatusIsFatal() && GetError().GetCode() != -44087)
+ {
+ if (dataSize != NULL)
+ *dataSize = 0;
+ return;
+ }
+
+ // Make sure we don't have more than one transaction with the same Jaguar outstanding.
+ semTake(m_transactionSemaphore, WAIT_FOREVER);
+
+ // Throw away any stale responses.
+ receiveMessage(&targetedMessageID, NULL, 0, 0.0f);
+ // Send the message requesting data.
+ localStatus = sendMessage(targetedMessageID, NULL, 0);
+ wpi_setErrorWithContext(localStatus, "sendMessage");
+ // Caller may have set bit31 for remote frame transmission so clear invalid bits[31-29]
+ targetedMessageID &= 0x1FFFFFFF;
+ // Wait for the data.
+ localStatus = receiveMessage(&targetedMessageID, data, dataSize);
+ wpi_setErrorWithContext(localStatus, "receiveMessage");
+
+ // Transaction complete.
+ semGive(m_transactionSemaphore);
+}
+
+/**
+ * Set the reference source device for speed controller mode.
+ *
+ * Choose encoder as the source of speed feedback when in speed control mode.
+ *
+ * @param reference Specify a SpeedReference.
+ */
+void CANJaguar::SetSpeedReference(SpeedReference reference)
+{
+ UINT8 dataBuffer[8];
+
+ dataBuffer[0] = reference;
+ setTransaction(LM_API_SPD_REF, dataBuffer, sizeof(UINT8));
+}
+
+/**
+ * Get the reference source device for speed controller mode.
+ *
+ * @return A SpeedReference indicating the currently selected reference device for speed controller mode.
+ */
+CANJaguar::SpeedReference CANJaguar::GetSpeedReference()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_SPD_REF, dataBuffer, &dataSize);
+ if (dataSize == sizeof(UINT8))
+ {
+ return (SpeedReference)*dataBuffer;
+ }
+ return kSpeedRef_None;
+}
+
+/**
+ * Set the reference source device for position controller mode.
+ *
+ * Choose between using and encoder and using a potentiometer
+ * as the source of position feedback when in position control mode.
+ *
+ * @param reference Specify a PositionReference.
+ */
+void CANJaguar::SetPositionReference(PositionReference reference)
+{
+ UINT8 dataBuffer[8];
+
+ dataBuffer[0] = reference;
+ setTransaction(LM_API_POS_REF, dataBuffer, sizeof(UINT8));
+}
+
+/**
+ * Get the reference source device for position controller mode.
+ *
+ * @return A PositionReference indicating the currently selected reference device for position controller mode.
+ */
+CANJaguar::PositionReference CANJaguar::GetPositionReference()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_POS_REF, dataBuffer, &dataSize);
+ if (dataSize == sizeof(UINT8))
+ {
+ return (PositionReference)*dataBuffer;
+ }
+ return kPosRef_None;
+}
+
+/**
+ * Set the P, I, and D constants for the closed loop modes.
+ *
+ * @param p The proportional gain of the Jaguar's PID controller.
+ * @param i The integral gain of the Jaguar's PID controller.
+ * @param d The differential gain of the Jaguar's PID controller.
+ */
+void CANJaguar::SetPID(double p, double i, double d)
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ switch(m_controlMode)
+ {
+ case kPercentVbus:
+ case kVoltage:
+ wpi_setWPIErrorWithContext(IncompatibleMode, "PID constants only apply in Speed, Position, and Current mode");
+ break;
+ case kSpeed:
+ dataSize = packFXP16_16(dataBuffer, p);
+ setTransaction(LM_API_SPD_PC, dataBuffer, dataSize);
+ dataSize = packFXP16_16(dataBuffer, i);
+ setTransaction(LM_API_SPD_IC, dataBuffer, dataSize);
+ dataSize = packFXP16_16(dataBuffer, d);
+ setTransaction(LM_API_SPD_DC, dataBuffer, dataSize);
+ break;
+ case kPosition:
+ dataSize = packFXP16_16(dataBuffer, p);
+ setTransaction(LM_API_POS_PC, dataBuffer, dataSize);
+ dataSize = packFXP16_16(dataBuffer, i);
+ setTransaction(LM_API_POS_IC, dataBuffer, dataSize);
+ dataSize = packFXP16_16(dataBuffer, d);
+ setTransaction(LM_API_POS_DC, dataBuffer, dataSize);
+ break;
+ case kCurrent:
+ dataSize = packFXP16_16(dataBuffer, p);
+ setTransaction(LM_API_ICTRL_PC, dataBuffer, dataSize);
+ dataSize = packFXP16_16(dataBuffer, i);
+ setTransaction(LM_API_ICTRL_IC, dataBuffer, dataSize);
+ dataSize = packFXP16_16(dataBuffer, d);
+ setTransaction(LM_API_ICTRL_DC, dataBuffer, dataSize);
+ break;
+ }
+}
+
+/**
+ * Get the Proportional gain of the controller.
+ *
+ * @return The proportional gain.
+ */
+double CANJaguar::GetP()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ switch(m_controlMode)
+ {
+ case kPercentVbus:
+ case kVoltage:
+ wpi_setWPIErrorWithContext(IncompatibleMode, "PID constants only apply in Speed, Position, and Current mode");
+ break;
+ case kSpeed:
+ getTransaction(LM_API_SPD_PC, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ break;
+ case kPosition:
+ getTransaction(LM_API_POS_PC, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ break;
+ case kCurrent:
+ getTransaction(LM_API_ICTRL_PC, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ break;
+ }
+ return 0.0;
+}
+
+/**
+ * Get the Intregral gain of the controller.
+ *
+ * @return The integral gain.
+ */
+double CANJaguar::GetI()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ switch(m_controlMode)
+ {
+ case kPercentVbus:
+ case kVoltage:
+ wpi_setWPIErrorWithContext(IncompatibleMode, "PID constants only apply in Speed, Position, and Current mode");
+ break;
+ case kSpeed:
+ getTransaction(LM_API_SPD_IC, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ break;
+ case kPosition:
+ getTransaction(LM_API_POS_IC, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ break;
+ case kCurrent:
+ getTransaction(LM_API_ICTRL_IC, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ break;
+ }
+ return 0.0;
+}
+
+/**
+ * Get the Differential gain of the controller.
+ *
+ * @return The differential gain.
+ */
+double CANJaguar::GetD()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ switch(m_controlMode)
+ {
+ case kPercentVbus:
+ case kVoltage:
+ wpi_setWPIErrorWithContext(IncompatibleMode, "PID constants only apply in Speed, Position, and Current mode");
+ break;
+ case kSpeed:
+ getTransaction(LM_API_SPD_DC, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ break;
+ case kPosition:
+ getTransaction(LM_API_POS_DC, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ break;
+ case kCurrent:
+ getTransaction(LM_API_ICTRL_DC, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ break;
+ }
+ return 0.0;
+}
+
+/**
+ * Enable the closed loop controller.
+ *
+ * Start actually controlling the output based on the feedback.
+ * If starting a position controller with an encoder reference,
+ * use the encoderInitialPosition parameter to initialize the
+ * encoder state.
+ *
+ * @param encoderInitialPosition Encoder position to set if position with encoder reference. Ignored otherwise.
+ */
+void CANJaguar::EnableControl(double encoderInitialPosition)
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize = 0;
+
+ switch(m_controlMode)
+ {
+ case kPercentVbus:
+ setTransaction(LM_API_VOLT_T_EN, dataBuffer, dataSize);
+ break;
+ case kSpeed:
+ setTransaction(LM_API_SPD_T_EN, dataBuffer, dataSize);
+ break;
+ case kPosition:
+ dataSize = packFXP16_16(dataBuffer, encoderInitialPosition);
+ setTransaction(LM_API_POS_T_EN, dataBuffer, dataSize);
+ break;
+ case kCurrent:
+ setTransaction(LM_API_ICTRL_T_EN, dataBuffer, dataSize);
+ break;
+ case kVoltage:
+ setTransaction(LM_API_VCOMP_T_EN, dataBuffer, dataSize);
+ break;
+ }
+}
+
+/**
+ * Disable the closed loop controller.
+ *
+ * Stop driving the output based on the feedback.
+ */
+void CANJaguar::DisableControl()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize = 0;
+
+ switch(m_controlMode)
+ {
+ case kPercentVbus:
+ setTransaction(LM_API_VOLT_DIS, dataBuffer, dataSize);
+ break;
+ case kSpeed:
+ setTransaction(LM_API_SPD_DIS, dataBuffer, dataSize);
+ break;
+ case kPosition:
+ setTransaction(LM_API_POS_DIS, dataBuffer, dataSize);
+ break;
+ case kCurrent:
+ setTransaction(LM_API_ICTRL_DIS, dataBuffer, dataSize);
+ break;
+ case kVoltage:
+ setTransaction(LM_API_VCOMP_DIS, dataBuffer, dataSize);
+ break;
+ }
+}
+
+/**
+ * Change the control mode of this Jaguar object.
+ *
+ * After changing modes, configure any PID constants or other settings needed
+ * and then EnableControl() to actually change the mode on the Jaguar.
+ *
+ * @param controlMode The new mode.
+ */
+void CANJaguar::ChangeControlMode(ControlMode controlMode)
+{
+ // Disable the previous mode
+ DisableControl();
+
+ // Update the local mode
+ m_controlMode = controlMode;
+
+ nUsageReporting::report(nUsageReporting::kResourceType_CANJaguar, m_deviceNumber, m_controlMode);
+}
+
+/**
+ * Get the active control mode from the Jaguar.
+ *
+ * Ask the Jag what mode it is in.
+ *
+ * @return ControlMode that the Jag is in.
+ */
+CANJaguar::ControlMode CANJaguar::GetControlMode()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_STATUS_CMODE, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT8))
+ {
+ return (ControlMode)dataBuffer[0];
+ }
+ return kPercentVbus;
+}
+
+/**
+ * Get the voltage at the battery input terminals of the Jaguar.
+ *
+ * @return The bus voltage in Volts.
+ */
+float CANJaguar::GetBusVoltage()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_STATUS_VOLTBUS, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT16))
+ {
+ return unpackFXP8_8(dataBuffer);
+ }
+ return 0.0;
+}
+
+/**
+ * Get the voltage being output from the motor terminals of the Jaguar.
+ *
+ * @return The output voltage in Volts.
+ */
+float CANJaguar::GetOutputVoltage()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ // Read the volt out which is in Volts units.
+ getTransaction(LM_API_STATUS_VOUT, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT16))
+ {
+ return unpackFXP8_8(dataBuffer);
+ }
+ return 0.0;
+}
+
+/**
+ * Get the current through the motor terminals of the Jaguar.
+ *
+ * @return The output current in Amps.
+ */
+float CANJaguar::GetOutputCurrent()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_STATUS_CURRENT, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT16))
+ {
+ return unpackFXP8_8(dataBuffer);
+ }
+ return 0.0;
+}
+
+/**
+ * Get the internal temperature of the Jaguar.
+ *
+ * @return The temperature of the Jaguar in degrees Celsius.
+ */
+float CANJaguar::GetTemperature()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_STATUS_TEMP, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT16))
+ {
+ return unpackFXP8_8(dataBuffer);
+ }
+ return 0.0;
+}
+
+/**
+ * Get the position of the encoder or potentiometer.
+ *
+ * @return The position of the motor in rotations based on the configured feedback.
+ */
+double CANJaguar::GetPosition()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_STATUS_POS, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ return 0.0;
+}
+
+/**
+ * Get the speed of the encoder.
+ *
+ * @return The speed of the motor in RPM based on the configured feedback.
+ */
+double CANJaguar::GetSpeed()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_STATUS_SPD, dataBuffer, &dataSize);
+ if (dataSize == sizeof(INT32))
+ {
+ return unpackFXP16_16(dataBuffer);
+ }
+ return 0.0;
+}
+
+/**
+ * Get the status of the forward limit switch.
+ *
+ * @return The motor is allowed to turn in the forward direction when true.
+ */
+bool CANJaguar::GetForwardLimitOK()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_STATUS_LIMIT, dataBuffer, &dataSize);
+ if (dataSize == sizeof(UINT8))
+ {
+ return (*dataBuffer & kForwardLimit) != 0;
+ }
+ return 0;
+}
+
+/**
+ * Get the status of the reverse limit switch.
+ *
+ * @return The motor is allowed to turn in the reverse direction when true.
+ */
+bool CANJaguar::GetReverseLimitOK()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_STATUS_LIMIT, dataBuffer, &dataSize);
+ if (dataSize == sizeof(UINT8))
+ {
+ return (*dataBuffer & kReverseLimit) != 0;
+ }
+ return 0;
+}
+
+/**
+ * Get the status of any faults the Jaguar has detected.
+ *
+ * @return A bit-mask of faults defined by the "Faults" enum.
+ */
+UINT16 CANJaguar::GetFaults()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_STATUS_FAULT, dataBuffer, &dataSize);
+ if (dataSize == sizeof(UINT16))
+ {
+ return unpackINT16(dataBuffer);
+ }
+ return 0;
+}
+
+/**
+ * Check if the Jaguar's power has been cycled since this was last called.
+ *
+ * This should return true the first time called after a Jaguar power up,
+ * and false after that.
+ *
+ * @return The Jaguar was power cycled since the last call to this function.
+ */
+bool CANJaguar::GetPowerCycled()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_STATUS_POWER, dataBuffer, &dataSize);
+ if (dataSize == sizeof(UINT8))
+ {
+ bool powerCycled = (*dataBuffer != 0);
+
+ // Clear the power cycled bit now that we've accessed it
+ if (powerCycled)
+ {
+ dataBuffer[0] = 1;
+ setTransaction(LM_API_STATUS_POWER, dataBuffer, sizeof(UINT8));
+ }
+
+ return powerCycled;
+ }
+ return 0;
+}
+
+/**
+ * Set the maximum voltage change rate.
+ *
+ * When in PercentVbus or Voltage output mode, the rate at which the voltage changes can
+ * be limited to reduce current spikes. Set this to 0.0 to disable rate limiting.
+ *
+ * @param rampRate The maximum rate of voltage change in Percent Voltage mode in V/s.
+ */
+void CANJaguar::SetVoltageRampRate(double rampRate)
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ switch(m_controlMode)
+ {
+ case kPercentVbus:
+ dataSize = packPercentage(dataBuffer, rampRate / (m_maxOutputVoltage * kControllerRate));
+ setTransaction(LM_API_VOLT_SET_RAMP, dataBuffer, dataSize);
+ break;
+ case kVoltage:
+ dataSize = packFXP8_8(dataBuffer, rampRate / kControllerRate);
+ setTransaction(LM_API_VCOMP_IN_RAMP, dataBuffer, dataSize);
+ break;
+ default:
+ return;
+ }
+}
+
+/**
+ * Get the version of the firmware running on the Jaguar.
+ *
+ * @return The firmware version. 0 if the device did not respond.
+ */
+UINT32 CANJaguar::GetFirmwareVersion()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ // Set the MSB to tell the 2CAN that this is a remote message.
+ getTransaction(0x80000000 | CAN_MSGID_API_FIRMVER, dataBuffer, &dataSize);
+ if (dataSize == sizeof(UINT32))
+ {
+ return unpackINT32(dataBuffer);
+ }
+ return 0;
+}
+
+/**
+ * Get the version of the Jaguar hardware.
+ *
+ * @return The hardware version. 1: Jaguar, 2: Black Jaguar
+ */
+UINT8 CANJaguar::GetHardwareVersion()
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ getTransaction(LM_API_HWVER, dataBuffer, &dataSize);
+ if (dataSize == sizeof(UINT8)+sizeof(UINT8))
+ {
+ if (*dataBuffer == m_deviceNumber)
+ {
+ return *(dataBuffer+1);
+ }
+ }
+ // Assume Gray Jag if there is no response
+ return LM_HWVER_JAG_1_0;
+}
+
+/**
+ * Configure what the controller does to the H-Bridge when neutral (not driving the output).
+ *
+ * This allows you to override the jumper configuration for brake or coast.
+ *
+ * @param mode Select to use the jumper setting or to override it to coast or brake.
+ */
+void CANJaguar::ConfigNeutralMode(NeutralMode mode)
+{
+ UINT8 dataBuffer[8];
+
+ dataBuffer[0] = mode;
+ setTransaction(LM_API_CFG_BRAKE_COAST, dataBuffer, sizeof(UINT8));
+}
+
+/**
+ * Configure how many codes per revolution are generated by your encoder.
+ *
+ * @param codesPerRev The number of counts per revolution in 1X mode.
+ */
+void CANJaguar::ConfigEncoderCodesPerRev(UINT16 codesPerRev)
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ dataSize = packINT16(dataBuffer, codesPerRev);
+ setTransaction(LM_API_CFG_ENC_LINES, dataBuffer, dataSize);
+}
+
+/**
+ * Configure the number of turns on the potentiometer.
+ *
+ * There is no special support for continuous turn potentiometers.
+ * Only integer numbers of turns are supported.
+ *
+ * @param turns The number of turns of the potentiometer
+ */
+void CANJaguar::ConfigPotentiometerTurns(UINT16 turns)
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ dataSize = packINT16(dataBuffer, turns);
+ setTransaction(LM_API_CFG_POT_TURNS, dataBuffer, dataSize);
+}
+
+/**
+ * Configure Soft Position Limits when in Position Controller mode.
+ *
+ * When controlling position, you can add additional limits on top of the limit switch inputs
+ * that are based on the position feedback. If the position limit is reached or the
+ * switch is opened, that direction will be disabled.
+ *
+ * @param forwardLimitPosition The position that if exceeded will disable the forward direction.
+ * @param reverseLimitPosition The position that if exceeded will disable the reverse direction.
+ */
+void CANJaguar::ConfigSoftPositionLimits(double forwardLimitPosition, double reverseLimitPosition)
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ dataSize = packFXP16_16(dataBuffer, forwardLimitPosition);
+ dataBuffer[dataSize++] = forwardLimitPosition > reverseLimitPosition;
+ setTransaction(LM_API_CFG_LIMIT_FWD, dataBuffer, dataSize);
+
+ dataSize = packFXP16_16(dataBuffer, reverseLimitPosition);
+ dataBuffer[dataSize++] = forwardLimitPosition <= reverseLimitPosition;
+ setTransaction(LM_API_CFG_LIMIT_REV, dataBuffer, dataSize);
+
+ dataBuffer[0] = kLimitMode_SoftPositionLimits;
+ setTransaction(LM_API_CFG_LIMIT_MODE, dataBuffer, sizeof(UINT8));
+}
+
+/**
+ * Disable Soft Position Limits if previously enabled.
+ *
+ * Soft Position Limits are disabled by default.
+ */
+void CANJaguar::DisableSoftPositionLimits()
+{
+ UINT8 dataBuffer[8];
+
+ dataBuffer[0] = kLimitMode_SwitchInputsOnly;
+ setTransaction(LM_API_CFG_LIMIT_MODE, dataBuffer, sizeof(UINT8));
+}
+
+/**
+ * Configure the maximum voltage that the Jaguar will ever output.
+ *
+ * This can be used to limit the maximum output voltage in all modes so that
+ * motors which cannot withstand full bus voltage can be used safely.
+ *
+ * @param voltage The maximum voltage output by the Jaguar.
+ */
+void CANJaguar::ConfigMaxOutputVoltage(double voltage)
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ m_maxOutputVoltage = voltage;
+ dataSize = packFXP8_8(dataBuffer, voltage);
+ setTransaction(LM_API_CFG_MAX_VOUT, dataBuffer, dataSize);
+}
+
+/**
+ * Configure how long the Jaguar waits in the case of a fault before resuming operation.
+ *
+ * Faults include over temerature, over current, and bus under voltage.
+ * The default is 3.0 seconds, but can be reduced to as low as 0.5 seconds.
+ *
+ * @param faultTime The time to wait before resuming operation, in seconds.
+ */
+void CANJaguar::ConfigFaultTime(float faultTime)
+{
+ UINT8 dataBuffer[8];
+ UINT8 dataSize;
+
+ // Message takes ms
+ dataSize = packINT16(dataBuffer, (INT16)(faultTime * 1000.0));
+ setTransaction(LM_API_CFG_FAULT_TIME, dataBuffer, dataSize);
+}
+
+/**
+ * Update all the motors that have pending sets in the syncGroup.
+ *
+ * @param syncGroup A bitmask of groups to generate synchronous output.
+ */
+void CANJaguar::UpdateSyncGroup(UINT8 syncGroup)
+{
+ sendMessage(CAN_MSGID_API_SYNC, &syncGroup, sizeof(syncGroup));
+}
+
+
+void CANJaguar::SetExpiration(float timeout)
+{
+ if (m_safetyHelper) m_safetyHelper->SetExpiration(timeout);
+}
+
+float CANJaguar::GetExpiration()
+{
+ if (!m_safetyHelper) return 0.0;
+ return m_safetyHelper->GetExpiration();
+}
+
+bool CANJaguar::IsAlive()
+{
+ if (!m_safetyHelper) return false;
+ return m_safetyHelper->IsAlive();
+}
+
+bool CANJaguar::IsSafetyEnabled()
+{
+ if (!m_safetyHelper) return false;
+ return m_safetyHelper->IsSafetyEnabled();
+}
+
+void CANJaguar::SetSafetyEnabled(bool enabled)
+{
+ if (m_safetyHelper) m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+void CANJaguar::GetDescription(char *desc)
+{
+ sprintf(desc, "CANJaguar ID %d", m_deviceNumber);
+}
+
+/**
+ * Common interface for stopping the motor
+ * Part of the MotorSafety interface
+ *
+ * @deprecated Call DisableControl instead.
+ */
+void CANJaguar::StopMotor()
+{
+ DisableControl();
+}
+
diff --git a/aos/externals/WPILib/WPILib/CANJaguar.h b/aos/externals/WPILib/WPILib/CANJaguar.h
new file mode 100644
index 0000000..f3cbee0
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CANJaguar.h
@@ -0,0 +1,120 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2009. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+
+#ifndef CANJAGUAR_H
+#define CANJAGUAR_H
+
+#include "ErrorBase.h"
+#include "MotorSafety.h"
+#include "MotorSafetyHelper.h"
+#include "PIDOutput.h"
+#include "SpeedController.h"
+#include <semLib.h>
+#include <vxWorks.h>
+
+/**
+ * Luminary Micro Jaguar Speed Control
+ */
+class CANJaguar : public MotorSafety, public PIDOutput, public SpeedController, public ErrorBase
+{
+public:
+ // The internal PID control loop in the Jaguar runs at 1kHz.
+ static const INT32 kControllerRate = 1000;
+ static const double kApproxBusVoltage = 12.0;
+
+ typedef enum {kPercentVbus, kCurrent, kSpeed, kPosition, kVoltage} ControlMode;
+ typedef enum {kCurrentFault = 1, kTemperatureFault = 2, kBusVoltageFault = 4, kGateDriverFault = 8} Faults;
+ typedef enum {kForwardLimit = 1, kReverseLimit = 2} Limits;
+ typedef enum {kPosRef_QuadEncoder = 0, kPosRef_Potentiometer = 1, kPosRef_None = 0xFF} PositionReference;
+ typedef enum {kSpeedRef_Encoder = 0, kSpeedRef_InvEncoder = 2, kSpeedRef_QuadEncoder = 3, kSpeedRef_None = 0xFF} SpeedReference;
+ typedef enum {kNeutralMode_Jumper = 0, kNeutralMode_Brake = 1, kNeutralMode_Coast = 2} NeutralMode;
+ typedef enum {kLimitMode_SwitchInputsOnly = 0, kLimitMode_SoftPositionLimits = 1} LimitMode;
+
+ explicit CANJaguar(UINT8 deviceNumber, ControlMode controlMode = kPercentVbus);
+ virtual ~CANJaguar();
+
+ // SpeedController interface
+ virtual float Get();
+ virtual void Set(float value, UINT8 syncGroup=0);
+ virtual void Disable();
+
+ // PIDOutput interface
+ virtual void PIDWrite(float output);
+
+ // Other Accessors
+ void SetSpeedReference(SpeedReference reference);
+ SpeedReference GetSpeedReference();
+ void SetPositionReference(PositionReference reference);
+ PositionReference GetPositionReference();
+ void SetPID(double p, double i, double d);
+ double GetP();
+ double GetI();
+ double GetD();
+ void EnableControl(double encoderInitialPosition = 0.0);
+ void DisableControl();
+ void ChangeControlMode(ControlMode controlMode);
+ ControlMode GetControlMode();
+ float GetBusVoltage();
+ float GetOutputVoltage();
+ float GetOutputCurrent();
+ float GetTemperature();
+ double GetPosition();
+ double GetSpeed();
+ bool GetForwardLimitOK();
+ bool GetReverseLimitOK();
+ UINT16 GetFaults();
+ bool GetPowerCycled();
+ void SetVoltageRampRate(double rampRate);
+ virtual UINT32 GetFirmwareVersion();
+ UINT8 GetHardwareVersion();
+ void ConfigNeutralMode(NeutralMode mode);
+ void ConfigEncoderCodesPerRev(UINT16 codesPerRev);
+ void ConfigPotentiometerTurns(UINT16 turns);
+ void ConfigSoftPositionLimits(double forwardLimitPosition, double reverseLimitPosition);
+ void DisableSoftPositionLimits();
+ void ConfigMaxOutputVoltage(double voltage);
+ void ConfigFaultTime(float faultTime);
+
+ static void UpdateSyncGroup(UINT8 syncGroup);
+
+ void SetExpiration(float timeout);
+ float GetExpiration();
+ bool IsAlive();
+ void StopMotor();
+ bool IsSafetyEnabled();
+ void SetSafetyEnabled(bool enabled);
+ void GetDescription(char *desc);
+
+protected:
+ UINT8 packPercentage(UINT8 *buffer, double value);
+ UINT8 packFXP8_8(UINT8 *buffer, double value);
+ UINT8 packFXP16_16(UINT8 *buffer, double value);
+ UINT8 packINT16(UINT8 *buffer, INT16 value);
+ UINT8 packINT32(UINT8 *buffer, INT32 value);
+ double unpackPercentage(UINT8 *buffer);
+ double unpackFXP8_8(UINT8 *buffer);
+ double unpackFXP16_16(UINT8 *buffer);
+ INT16 unpackINT16(UINT8 *buffer);
+ INT32 unpackINT32(UINT8 *buffer);
+ virtual void setTransaction(UINT32 messageID, const UINT8 *data, UINT8 dataSize);
+ virtual void getTransaction(UINT32 messageID, UINT8 *data, UINT8 *dataSize);
+
+ static INT32 sendMessage(UINT32 messageID, const UINT8 *data, UINT8 dataSize);
+ static INT32 receiveMessage(UINT32 *messageID, UINT8 *data, UINT8 *dataSize, float timeout = 0.02);
+
+ UINT8 m_deviceNumber;
+ ControlMode m_controlMode;
+ SEM_ID m_transactionSemaphore;
+ double m_maxOutputVoltage;
+
+ MotorSafetyHelper *m_safetyHelper;
+
+private:
+ void InitCANJaguar();
+};
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CAccelerometer.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CAccelerometer.cpp
new file mode 100644
index 0000000..d8ba69c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CAccelerometer.cpp
@@ -0,0 +1,186 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Accelerometer.h"
+#include "CInterfaces/CAccelerometer.h"
+#include "AnalogModule.h"
+#include "CInterfaces/CWrappers.h"
+
+static Accelerometer* accelerometers[SensorBase::kAnalogModules][SensorBase::kAnalogChannels];
+static bool initialized = false;
+
+/**
+ * Allocate an instance of the C Accelerometer object
+ * @param slot The slot the analog module is plugged into
+ * @param channel The analog module channel the accelerometer is plugged into
+ */
+static Accelerometer *AllocateAccelerometer(UINT8 moduleNumber, UINT32 channel)
+{
+ if (!initialized)
+ {
+ initialized = true;
+ for (unsigned i = 1; i <= SensorBase::kAnalogModules; i++)
+ for (unsigned j = 1; j <= SensorBase::kAnalogChannels; j++)
+ accelerometers[i][j] = NULL;
+ }
+ if (!SensorBase::CheckAnalogModule(moduleNumber) || !SensorBase::CheckAnalogChannel(channel))
+ return NULL;
+ unsigned index = moduleNumber - 1;
+ if (accelerometers[index][channel - 1] == NULL)
+ {
+ accelerometers[index][channel - 1] = new Accelerometer(moduleNumber, channel);
+ }
+ return accelerometers[index][channel - 1];
+}
+
+/**
+ * Get the acceleration in Gs
+ * @param channel The channel the accelerometer is plugged into
+ * @returns Returns the acceleration in Gs
+ */
+float GetAcceleration(UINT32 channel)
+{
+ Accelerometer *accel = AllocateAccelerometer(SensorBase::GetDefaultAnalogModule(), channel);
+ return accel->GetAcceleration();
+}
+
+/**
+ * Get the acceleration in Gs
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel the accelerometer is plugged into
+ * @returns Returns the acceleration in Gs
+ */
+float GetAcceleration(UINT8 moduleNumber, UINT32 channel)
+{
+ Accelerometer *accel = AllocateAccelerometer(moduleNumber, channel);
+ return accel->GetAcceleration();
+}
+
+/**
+ * Set the accelerometer sensitivity.
+ *
+ * This sets the sensitivity of the accelerometer used for calculating the acceleration.
+ * The sensitivity varys by accelerometer model. There are constants defined for various models.
+ *
+ * @param channel The channel the accelerometer is plugged into
+ * @param sensitivity The sensitivity of accelerometer in Volts per G.
+ */
+void SetAccelerometerSensitivity(UINT32 channel, float sensitivity)
+{
+ Accelerometer *accel = AllocateAccelerometer(SensorBase::GetDefaultAnalogModule(), channel);
+ accel->SetSensitivity(sensitivity);
+}
+
+/**
+ * Set the accelerometer sensitivity.
+ *
+ * This sets the sensitivity of the accelerometer used for calculating the acceleration.
+ * The sensitivity varys by accelerometer model. There are constants defined for various models.
+ *
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel the accelerometer is plugged into
+ * @param sensitivity The sensitivity of accelerometer in Volts per G.
+ */
+void SetAccelerometerSensitivity(UINT8 moduleNumber, UINT32 channel, float sensitivity)
+{
+ Accelerometer *accel = AllocateAccelerometer(moduleNumber, channel);
+ accel->SetSensitivity(sensitivity);
+}
+
+/**
+ * Set the voltage that corresponds to 0 G.
+ *
+ * The zero G voltage varys by accelerometer model. There are constants defined for various models.
+ *
+ * @param channel The channel the accelerometer is plugged into
+ * @param zero The zero G voltage.
+ */
+void SetAccelerometerZero(UINT32 channel, float zero)
+{
+ Accelerometer *accel = AllocateAccelerometer(SensorBase::GetDefaultAnalogModule(), channel);
+ accel->SetZero(zero);
+}
+
+/**
+ * Set the voltage that corresponds to 0 G.
+ *
+ * The zero G voltage varys by accelerometer model. There are constants defined for various models.
+ *
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel the accelerometer is plugged into
+ * @param zero The zero G voltage.
+ */
+void SetAccelerometerZero(UINT8 moduleNumber, UINT32 channel, float zero)
+{
+ Accelerometer *accel = AllocateAccelerometer(moduleNumber, channel);
+ accel->SetZero(zero);
+}
+
+/**
+ * Delete the accelerometer underlying object
+ * Deletes the object that is associated with this accelerometer and frees up the storage
+ * and the ports.
+ *
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel the accelerometer is plugged into
+ */
+void DeleteAccelerometer(UINT8 moduleNumber, UINT32 channel)
+{
+ if (SensorBase::CheckAnalogModule(moduleNumber) && SensorBase::CheckAnalogChannel(channel))
+ {
+ unsigned index = moduleNumber - 1;
+ delete accelerometers[index][channel - 1];
+ accelerometers[index][channel - 1] = NULL;
+ }
+}
+
+/**
+ * Delete the accelerometer underlying object
+ * Deletes the object that is associated with this accelerometer and frees up the storage
+ * and the ports.
+ *
+ * @param channel The channel the accelerometer is plugged into
+ */
+void DeleteAccelerometer(UINT32 channel)
+{
+ DeleteAccelerometer(SensorBase::GetDefaultAnalogModule(), channel);
+}
+
+
+/**
+ * Alternate C Interface
+ */
+
+AccelerometerObject CreateAccelerometer(UINT32 channel)
+{
+ return (AccelerometerObject) new Accelerometer(channel);
+}
+
+AccelerometerObject CreateAccelerometer(UINT8 moduleNumber, UINT32 channel)
+{
+ return (AccelerometerObject) new Accelerometer(moduleNumber, channel);
+}
+
+float GetAcceleration(AccelerometerObject o)
+{
+ return ((Accelerometer *) o)->GetAcceleration();
+}
+
+void SetAccelerometerSensitivity(AccelerometerObject o, float sensitivity)
+{
+ ((Accelerometer *) o)->SetSensitivity(sensitivity);
+}
+
+void SetAccelerometerZero(AccelerometerObject o, float zero)
+{
+ ((Accelerometer *)o )->SetZero(zero);
+}
+
+void DeleteAccelerometer(AccelerometerObject o)
+{
+ delete (Accelerometer *) o;
+}
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CAccelerometer.h b/aos/externals/WPILib/WPILib/CInterfaces/CAccelerometer.h
new file mode 100644
index 0000000..90f3113
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CAccelerometer.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef _C_ACCELEROMETER_H
+#define _C_ACCELEROMETER_H
+
+float GetAcceleration(UINT32 channel);
+float GetAcceleration(UINT8 moduleNumber, UINT32 channel);
+void SetAccelerometerSensitivity(UINT32 channel, float sensitivity);
+void SetAccelerometerSensitivity(UINT8 moduleNumber, UINT32 channel, float sensitivity);
+void SetAccelerometerZero(UINT32 channel, float zero);
+void SetAccelerometerZero(UINT8 moduleNumber, UINT32 channel, float zero);
+void DeleteAccelerometer(UINT32 channel);
+void DeleteAccelerometer(UINT8 moduleNumber, UINT32 channel);
+
+typedef void *AccelerometerObject;
+
+AccelerometerObject CreateAccelerometer(UINT32 channel);
+AccelerometerObject CreateAccelerometer(UINT8 moduleNumber, UINT32 channel);
+float GetAcceleration(AccelerometerObject o);
+void SetAccelerometerSensitivity(AccelerometerObject o, float sensitivity);
+void SetAccelerometerZero(AccelerometerObject o, float zero);
+void DeleteAccelerometer(AccelerometerObject o);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CAnalogChannel.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CAnalogChannel.cpp
new file mode 100644
index 0000000..cf0f675
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CAnalogChannel.cpp
@@ -0,0 +1,422 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "CInterfaces/CAnalogChannel.h"
+#include "AnalogModule.h"
+
+static bool analogChannelsInitialized = false;
+static AnalogChannel
+ *analogs[SensorBase::kAnalogModules][SensorBase::kAnalogChannels];
+
+/**
+ * Allocate an AnalogChannel object for this set of slot/port
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel number on the module for this analog channel object
+ */
+AnalogChannel *AllocateAnalogChannel(UINT8 moduleNumber, UINT32 channel/*, SensorCreator createObject*/)
+{
+ if (!analogChannelsInitialized)
+ {
+ for (unsigned i = 0; i < SensorBase::kAnalogModules; i++)
+ for (unsigned j = 0; j < SensorBase::kAnalogChannels; j++)
+ analogs[i][j] = NULL;
+ analogChannelsInitialized = true;
+ }
+ if (SensorBase::CheckAnalogModule(moduleNumber) && SensorBase::CheckAnalogChannel(channel))
+ {
+ if (analogs[moduleNumber - 1][channel - 1] == NULL)
+ analogs[moduleNumber - 1][channel - 1] = new AnalogChannel(moduleNumber, channel);
+ return analogs[moduleNumber - 1][channel - 1];
+ }
+ else
+ return NULL;
+}
+
+/**
+ * Get a sample straight from this channel on the module.
+ * The sample is a 12-bit value representing the -10V to 10V range of the A/D converter in the module.
+ * The units are in A/D converter codes. Use GetVoltage() to get the analog value in calibrated units.
+ *
+ * @param slot The slot the analog module is plugged into
+ * @param channel the channel for the value being used
+ * @return A sample straight from this channel on the module.
+ */
+INT16 GetAnalogValue(UINT8 moduleNumber, UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(moduleNumber, channel);
+ if (analog != NULL)
+ {
+ return analog->GetValue();
+ }
+ return 0;
+}
+
+/**
+ * Get a sample from the output of the oversample and average engine for this channel.
+ * The sample is 12-bit + the value configured in SetOversampleBits().
+ * The value configured in SetAverageBits() will cause this value to be averaged 2**bits number of samples.
+ * This is not a sliding window. The sample will not change until 2**(OversamplBits + AverageBits) samples
+ * have been acquired from the module on this channel.
+ * Use GetAverageVoltage() to get the analog value in calibrated units.
+ *
+ * @param slot The slot the analog module is plugged into
+ * @param channel the channel for the value being used
+ * @return A sample from the oversample and average engine for this channel.
+ */
+INT32 GetAnalogAverageValue(UINT8 moduleNumber, UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(moduleNumber, channel);
+ if (analog != NULL)
+ {
+ return analog->GetAverageValue();
+ }
+ return 0;
+}
+
+/**
+ * Get a scaled sample straight from this channel on the module.
+ * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset().
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel in the module assicated with this analog channel
+ * @return A scaled sample straight from this channel on the module.
+ */
+float GetAnalogVoltage(UINT8 moduleNumber, UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(moduleNumber, channel);
+ if (analog != NULL)
+ {
+ return analog->GetVoltage();
+ }
+ return 0.0;
+}
+
+/**
+ * Get a scaled sample from the output of the oversample and average engine for this channel.
+ * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset().
+ * Using oversampling will cause this value to be higher resolution, but it will update more slowly.
+ * Using averaging will cause this value to be more stable, but it will update more slowly.
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel in the module assicated with this analog channel
+ * @return A scaled sample from the output of the oversample and average engine for this channel.
+ */
+float GetAnalogAverageVoltage(UINT8 moduleNumber, UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(moduleNumber, channel);
+ if (analog != NULL)
+ {
+ return analog->GetAverageVoltage();
+ }
+ return 0.0;
+}
+
+/**
+ * Set the number of averaging bits.
+ * This sets the number of averaging bits. The actual number of averaged samples is 2**bits.
+ * Use averaging to improve the stability of your measurement at the expense of sampling rate.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel in the module assicated with this analog channel
+ * @param bits Number of bits of averaging.
+ */
+void SetAnalogAverageBits(UINT8 moduleNumber, UINT32 channel, UINT32 bits)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(moduleNumber, channel);
+ if (analog != NULL)
+ {
+ analog->SetAverageBits(bits);
+ }
+}
+
+/**
+ * Get the number of averaging bits previously configured.
+ * This gets the number of averaging bits from the FPGA. The actual number of averaged samples is 2**bits.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel in the module assicated with this analog channel
+ * @return Number of bits of averaging previously configured.
+ */
+UINT32 GetAnalogAverageBits(UINT8 moduleNumber, UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(moduleNumber, channel);
+ if (analog != NULL)
+ {
+ return analog->GetAverageBits();
+ }
+ return 0;
+}
+
+/**
+ * Set the number of oversample bits.
+ * This sets the number of oversample bits. The actual number of oversampled values is 2**bits.
+ * Use oversampling to improve the resolution of your measurements at the expense of sampling rate.
+ * The oversampling is done automatically in the FPGA.
+ *
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel in the module assicated with this analog channel
+ * @param bits Number of bits of oversampling.
+ */
+void SetAnalogOversampleBits(UINT8 moduleNumber, UINT32 channel, UINT32 bits)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(moduleNumber, channel);
+ if (analog != NULL)
+ {
+ analog->SetOversampleBits(bits);
+ }
+}
+
+/**
+ * Get the number of oversample bits previously configured.
+ * This gets the number of oversample bits from the FPGA. The actual number of oversampled values is
+ * 2**bits. The oversampling is done automatically in the FPGA.
+ *
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel in the module assicated with this analog channel
+ * @return Number of bits of oversampling previously configured.
+ */
+UINT32 GetAnalogOversampleBits(UINT8 moduleNumber, UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(moduleNumber, channel);
+ if (analog != NULL)
+ {
+ return analog->GetOversampleBits();
+ }
+ return 0;
+}
+
+/**
+ * Get a sample straight from this channel on the module.
+ * The sample is a 12-bit value representing the -10V to 10V range of the A/D converter in the module.
+ * The units are in A/D converter codes. Use GetVoltage() to get the analog value in calibrated units.
+
+ * @param channel The channel in the module assicated with this analog channel
+ * @return A sample straight from this channel on the module.
+ */
+INT16 GetAnalogValue(UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(AnalogModule::GetDefaultAnalogModule(), channel);
+ if (analog != NULL)
+ {
+ return analog->GetValue();
+ }
+ return 0;
+}
+
+/**
+ * Get a sample from the output of the oversample and average engine for this channel.
+ * The sample is 12-bit + the value configured in SetOversampleBits().
+ * The value configured in SetAverageBits() will cause this value to be averaged 2**bits number of samples.
+ * This is not a sliding window. The sample will not change until 2**(OversamplBits + AverageBits) samples
+ * have been acquired from the module on this channel.
+ * Use GetAverageVoltage() to get the analog value in calibrated units.
+
+ * @param channel The channel in the module assicated with this analog channel
+ * @return A sample from the oversample and average engine for this channel.
+ */
+INT32 GetAnalogAverageValue(UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(AnalogModule::GetDefaultAnalogModule(), channel);
+ if (analog != NULL)
+ {
+ return analog->GetAverageValue();
+ }
+ return 0;
+}
+
+/**
+ * Get a scaled sample straight from this channel on the module.
+ * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset().
+
+ * @param channel The channel in the module assicated with this analog channel
+ * @return A scaled sample straight from this channel on the module.
+ */
+float GetAnalogVoltage(UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(AnalogModule::GetDefaultAnalogModule(), channel);
+ if (analog != NULL)
+ {
+ return analog->GetVoltage();
+ }
+ return 0.0;
+}
+
+/**
+ * Get a scaled sample from the output of the oversample and average engine for this channel.
+ * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset().
+ * Using oversampling will cause this value to be higher resolution, but it will update more slowly.
+ * Using averaging will cause this value to be more stable, but it will update more slowly.
+
+ * @param channel The channel in the module assicated with this analog channel
+ * @return A scaled sample from the output of the oversample and average engine for this channel.
+ */
+float GetAnalogAverageVoltage(UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(AnalogModule::GetDefaultAnalogModule(), channel);
+ if (analog != NULL)
+ {
+ return analog->GetAverageVoltage();
+ }
+ return 0.0;
+}
+
+/**
+ * Set the number of averaging bits.
+ * This sets the number of averaging bits. The actual number of averaged samples is 2**bits.
+ * Use averaging to improve the stability of your measurement at the expense of sampling rate.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @param channel The channel in the module assicated with this analog channel
+ * @param bits Number of bits of averaging.
+ */
+void SetAnalogAverageBits(UINT32 channel, UINT32 bits)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(AnalogModule::GetDefaultAnalogModule(), channel);
+ if (analog != NULL)
+ {
+ analog->SetAverageBits(bits);
+ }
+}
+
+/**
+ * Get the number of averaging bits previously configured.
+ * This gets the number of averaging bits from the FPGA. The actual number of averaged samples is 2**bits.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @param channel The channel in the module assicated with this analog channel
+ * @return Number of bits of averaging previously configured.
+ */
+UINT32 GetAnalogAverageBits(UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(AnalogModule::GetDefaultAnalogModule(), channel);
+ if (analog != NULL)
+ {
+ return analog->GetAverageBits();
+ }
+ return 0;
+}
+
+/**
+ * Set the number of oversample bits.
+ * This sets the number of oversample bits. The actual number of oversampled values is 2**bits.
+ * Use oversampling to improve the resolution of your measurements at the expense of sampling rate.
+ * The oversampling is done automatically in the FPGA.
+ *
+ * @param channel The channel in the module assicated with this analog channel
+ * @param bits Number of bits of oversampling.
+ */
+void SetAnalogOversampleBits(UINT32 channel, UINT32 bits)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(AnalogModule::GetDefaultAnalogModule(), channel);
+ if (analog != NULL)
+ {
+ analog->GetOversampleBits();
+ }
+}
+
+/**
+ * Get the number of oversample bits previously configured.
+ * This gets the number of oversample bits from the FPGA. The actual number of oversampled values is
+ * 2**bits. The oversampling is done automatically in the FPGA.
+ *
+ * @param channel The channel in the module assicated with this analog channel
+ * @return Number of bits of oversampling previously configured.
+ */
+UINT32 GetAnalogOversampleBits(UINT32 channel)
+{
+ AnalogChannel *analog = AllocateAnalogChannel(AnalogModule::GetDefaultAnalogModule(), channel);
+ if (analog != NULL)
+ {
+ return analog->GetOversampleBits();
+ }
+ return 0;
+}
+
+/**
+ * Delete the resources associated with this AnalogChannel
+ * The underlying object and the port reservations are deleted for this analog channel.
+
+ * @param slot The slot the analog module is plugged into
+ * @param channel The channel in the module assicated with this analog channel
+ */
+void DeleteAnalogChannel(UINT8 moduleNumber, UINT32 channel)
+{
+ if (SensorBase::CheckAnalogModule(moduleNumber) && SensorBase::CheckAnalogChannel(channel))
+ {
+ delete analogs[moduleNumber - 1][channel - 1];
+ analogs[moduleNumber - 1][channel - 1] = NULL;
+ }
+}
+
+/**
+ * Delete the resources associated with this AnalogChannel
+ * The underlying object and the port reservations are deleted for this analog channel.
+
+ * @param channel The channel in the module assicated with this analog channel
+ */
+void DeleteAnalogChannel(UINT32 channel)
+{
+ DeleteAnalogChannel(SensorBase::GetDefaultAnalogModule(), channel);
+}
+
+/**
+ * Alternative C Interface
+ */
+
+AnalogChannelObject CreateAnalogChannel(UINT32 module, UINT32 channel)
+{
+ return (AnalogChannelObject) new AnalogChannel(module, channel);
+}
+
+AnalogChannelObject CreateAnalogChannel(UINT32 channel)
+{
+ return (AnalogChannelObject) new AnalogChannel(channel);
+}
+
+INT16 GetAnalogValue(AnalogChannelObject o)
+{
+ return ((AnalogChannel *)o )->GetValue();
+}
+
+INT32 GetAnalogAverageValue(AnalogChannelObject o)
+{
+ return ((AnalogChannel *)o )->GetAverageValue();
+}
+
+float GetAnalogVoltage(AnalogChannelObject o)
+{
+ return ((AnalogChannel *)o )->GetVoltage();
+}
+
+float GetAnalogAverageVoltage(AnalogChannelObject o)
+{
+ return ((AnalogChannel *)o )->GetAverageVoltage();
+}
+
+void SetAnalogAverageBits(AnalogChannelObject o, UINT32 bits)
+{
+ ((AnalogChannel *)o )->SetAverageBits(bits);
+}
+
+UINT32 GetAnalogAverageBits(AnalogChannelObject o)
+{
+ return ((AnalogChannel *)o )->GetAverageBits();
+}
+
+void SetAnalogOversampleBits(AnalogChannelObject o, UINT32 bits)
+{
+ ((AnalogChannel *)o )->SetOversampleBits(bits);
+}
+
+UINT32 GetAnalogOversampleBits(AnalogChannelObject o)
+{
+ return ((AnalogChannel *)o )->GetOversampleBits();
+}
+
+void DeleteAnalogChannel(AnalogChannelObject o)
+{
+ delete (AnalogChannel *)o;
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CAnalogChannel.h b/aos/externals/WPILib/WPILib/CInterfaces/CAnalogChannel.h
new file mode 100644
index 0000000..55206b0
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CAnalogChannel.h
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef C_ANALOG_CHANNEL_H
+#define C_ANALOG_CHANNEL_H
+
+#include "AnalogChannel.h"
+#include "CWrappers.h"
+
+AnalogChannel *AllocateAnalogChannel(UINT8 moduleNumber, UINT32 channel /*,SensorCreator createObject*/);
+
+INT16 GetAnalogValue(UINT8 moduleNumber, UINT32 channel);
+INT32 GetAnalogAverageValue(UINT8 moduleNumber, UINT32 channel);
+
+float GetAnalogVoltage(UINT8 moduleNumber, UINT32 channel);
+float GetAnalogAverageVoltage(UINT8 moduleNumber, UINT32 channel);
+
+void SetAnalogAverageBits(UINT8 moduleNumber, UINT32 channel, UINT32 bits);
+UINT32 GetAnalogAverageBits(UINT8 moduleNumber, UINT32 channel);
+void SetAnalogOversampleBits(UINT8 moduleNumber, UINT32 channel, UINT32 bits);
+UINT32 GetAnalogOversampleBits(UINT8 moduleNumber, UINT32 channel);
+
+INT16 GetAnalogValue(UINT32 channel);
+INT32 GetAnalogAverageValue(UINT32 channel);
+
+float GetAnalogVoltage(UINT32 channel);
+float GetAnalogAverageVoltage(UINT32 channel);
+
+void SetAnalogAverageBits(UINT32 channel, UINT32 bits);
+UINT32 GetAnalogAverageBits(UINT32 channel);
+void SetAnalogOversampleBits(UINT32 channel, UINT32 bits);
+UINT32 GetAnalogOversampleBits(UINT32 channel);
+
+UINT32 GetAnalogLSBWeight();
+INT32 GetAnalogOffset();
+
+void DeleteAnalogChannel(UINT8 moduleNumber, UINT32 channel);
+void DeleteAnalogChannel(UINT32 channel);
+
+typedef void *AnalogChannelObject;
+
+AnalogChannelObject CreateAnalogChannel(UINT8 moduleNumber, UINT32 channel);
+AnalogChannelObject CreateAnalogChannel(UINT32 channel);
+INT16 GetAnalogValue(AnalogChannelObject o);
+INT32 GetAnalogAverageValue(AnalogChannelObject o);
+
+float GetAnalogVoltage(AnalogChannelObject o);
+float GetAnalogAverageVoltage(AnalogChannelObject o);
+
+void SetAnalogAverageBits(AnalogChannelObject o, UINT32 bits);
+UINT32 GetAnalogAverageBits(AnalogChannelObject o);
+void SetAnalogOversampleBits(AnalogChannelObject o, UINT32 bits);
+UINT32 GetAnalogOversampleBits(AnalogChannelObject o);
+void DeleteAnalogChannel(AnalogChannelObject o);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CCompressor.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CCompressor.cpp
new file mode 100644
index 0000000..233b84c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CCompressor.cpp
@@ -0,0 +1,107 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Compressor.h"
+#include "CInterfaces/CCompressor.h"
+#include "CInterfaces/CError.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+static Compressor *compressor = NULL;
+
+/**
+ * Allocate resources for a compressor/pressure switch pair
+ * Allocate the underlying object for the compressor.
+ * @param pressureSwitchChannel The channel on the default digital module for the pressure switch
+ * @param relayChannel The channel on the default digital module for the relay that controls the compressor
+ */
+void CreateCompressor(UINT32 pressureSwitchChannel, UINT32 relayChannel)
+{
+ if (compressor == NULL)
+ {
+ compressor = new Compressor(pressureSwitchChannel, relayChannel);
+ return;
+ }
+ CError *error = new CError();
+ wpi_setStaticWPIError(error, CompressorAlreadyDefined);
+}
+
+/**
+ * Allocate resources for a compressor/pressure switch pair
+ * Allocate the underlying object for the compressor.
+ * @param pressureSwitchSlot The slot of the digital module for the pressure switch
+ * @param pressureSwitchChannel The channel on the digital module for the pressure switch
+ * @param relaySlot The slot of the digital module for the relay controlling the compressor
+ * @param relayChannel The channel on the digital module for the relay that controls the compressor
+ */
+void CreateCompressor(UINT32 pressureSwitchSlot, UINT32 pressureSwitchChannel,
+ UINT32 relaySlot, UINT32 relayChannel)
+{
+ if (compressor == NULL)
+ {
+ compressor = new Compressor(pressureSwitchSlot, pressureSwitchChannel,
+ relaySlot, relayChannel);
+ return;
+ }
+ CError *error = new CError();
+ wpi_setStaticWPIError(error, CompressorAlreadyDefined);
+}
+
+/**
+ * Start the compressor
+ * Calling this function will cause the compressor task to begin polling the switch and operating the compressor.
+ */
+void StartCompressor()
+{
+ if (compressor == NULL)
+ {
+ CError *error = new CError();
+ wpi_setStaticWPIError(error, CompressorUndefined);
+ return;
+ }
+ compressor->Start();
+}
+
+/**
+ * Stop the compressor.
+ * Stops the polling loop that operates the compressor. At this time the compressor will stop operating.
+ */
+void StopCompressor()
+{
+ if (compressor == NULL)
+ {
+ CError *error = new CError();
+ wpi_setStaticWPIError(error, CompressorUndefined);
+ return;
+ }
+ compressor->Stop();
+}
+
+/**
+ * Get the state of the enabled flag.
+ * Return the state of the enabled flag for the compressor and pressure switch.
+ *
+ * @return The state of the compressor task's enable flag.
+ */
+bool CompressorEnabled()
+{
+ if (compressor == NULL)
+ {
+ CError *error = new CError();
+ wpi_setStaticWPIError(error, CompressorUndefined);
+ return false;
+ }
+ return compressor->Enabled();
+}
+
+/**
+ * Free the resources associated with the compressor.
+ * The underlying Compressor object will be deleted and the resources and ports freed.
+ */
+void DeleteCompressor()
+{
+ delete compressor;
+}
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CCompressor.h b/aos/externals/WPILib/WPILib/CInterfaces/CCompressor.h
new file mode 100644
index 0000000..2047de0
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CCompressor.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef _COMPRESSOR_H
+#define _COMPRESSOR_H
+
+void CreateCompressor(UINT32 pressureSwitch, UINT32 relayChannel);
+void CreateCompressor(UINT32 pressureSwitchSlot, UINT32 pressureSwitchChannel,
+ UINT32 relaySlot, UINT32 relayChannel);
+void StartCompressor();
+void StopCompressor();
+bool CompressorEnabled();
+
+void DeleteCompressor();
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CCounter.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CCounter.cpp
new file mode 100644
index 0000000..72eb5f7
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CCounter.cpp
@@ -0,0 +1,264 @@
+#include "VxWorks.h"
+#include "CInterfaces/CCounter.h"
+#include "Counter.h"
+#include "DigitalModule.h"
+
+static Counter* counters[SensorBase::kDigitalModules][SensorBase::kDigitalChannels];
+static bool initialized = false;
+
+/**
+ * Allocate the resource for a counter
+ * Allocate the underlying Counter object and the resources associated with the
+ * slot and channel
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The channel of the digital input used with this counter
+ */
+static Counter *AllocateCounter(UINT8 moduleNumber, UINT32 channel)
+{
+ if (!initialized)
+ {
+ for (unsigned i = 0; i < SensorBase::kDigitalModules; i++)
+ for (unsigned j = 0; j < SensorBase::kDigitalChannels; j++)
+ counters[i][j] = NULL;
+ initialized = true;
+ }
+ if (SensorBase::CheckDigitalModule(moduleNumber) && SensorBase::CheckDigitalChannel(channel))
+ {
+ UINT32 slotOffset = moduleNumber - 1;
+ if (counters[slotOffset][channel - 1] == NULL)
+ counters[slotOffset][channel - 1] = new Counter(moduleNumber, channel);
+ return counters[slotOffset][channel - 1];
+ }
+ else
+ return NULL;
+}
+
+/**
+ * Allocate the resource for a counter
+ * Allocate the underlying Counter object and the resources associated with the
+ * slot and channel
+ *
+ * @param channel The channel of the digital input used with this counter
+ */
+static Counter *AllocateCounter(UINT32 channel)
+{
+ return AllocateCounter(DigitalModule::GetDefaultDigitalModule(), channel);
+}
+
+/**
+ * Start the Counter counting.
+ * This enables the counter and it starts accumulating counts from the associated
+ * input channel. The counter value is not reset on starting, and still has the previous value.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The channel of the digital input used with this counter
+ */
+void StartCounter(UINT8 moduleNumber, UINT32 channel)
+{
+ Counter *counter = AllocateCounter(moduleNumber, channel);
+ if (counter != NULL)
+ counter->Start();
+}
+
+/**
+ * Start the Counter counting.
+ * This enables the counter and it starts accumulating counts from the associated
+ * input channel. The counter value is not reset on starting, and still has the previous value.
+ *
+ * @param channel The channel of the digital input used with this counter
+ */
+void StartCounter(UINT32 channel)
+{
+ Counter *counter = AllocateCounter(channel);
+ if (counter != NULL)
+ counter->Start();
+}
+
+/**
+ * Read the current counter value.
+ * Read the value at this instant. It may still be running, so it reflects the current value. Next
+ * time it is read, it might have a different value.
+
+ * @param channel The channel of the digital input used with this counter
+ */
+INT32 GetCounter(UINT32 channel)
+{
+ Counter *counter = AllocateCounter(channel);
+ if (counter != NULL)
+ return counter->Get();
+ else
+ return 0;
+}
+
+/**
+ * Read the current counter value.
+ * Read the value at this instant. It may still be running, so it reflects the current value. Next
+ * time it is read, it might have a different value.
+
+ * @param slot The slot the digital module is plugged into
+ * @param channel The channel of the digital input used with this counter
+ */
+INT32 GetCounter(UINT8 moduleNumber, UINT32 channel)
+{
+ Counter *counter = AllocateCounter(moduleNumber, channel);
+ if (counter != NULL)
+ return counter->Get();
+ else
+ return 0;
+}
+
+/**
+ * Reset the Counter to zero.
+ * Set the counter value to zero. This doesn't effect the running state of the counter, just sets
+ * the current value to zero.
+ * @param channel The channel of the digital input used with this counter
+ */
+void ResetCounter(UINT32 channel)
+{
+ Counter *counter = AllocateCounter(channel);
+ if (counter != NULL)
+ counter->Reset();
+}
+
+/**
+ * Reset the Counter to zero.
+ * Set the counter value to zero. This doesn't effect the running state of the counter, just sets
+ * the current value to zero.
+ * @param slot The slot the digital module is plugged into
+ * @param channel The channel of the digital input used with this counter
+ */
+void ResetCounter(UINT8 moduleNumber, UINT32 channel)
+{
+ Counter *counter = AllocateCounter(moduleNumber, channel);
+ if (counter != NULL)
+ counter->Reset();
+}
+
+/**
+ * Stop the Counter.
+ * Stops the counting but doesn't effect the current value.
+ * @param slot The slot the digital module is plugged into
+ * @param channel The channel of the digital input used with this counter
+ */
+void StopCounter(UINT8 moduleNumber, UINT32 channel)
+{
+ Counter *counter = AllocateCounter(moduleNumber, channel);
+ if (counter != NULL)
+ counter->Stop();
+}
+
+/**
+ * Stop the Counter.
+ * Stops the counting but doesn't effect the current value.
+ * @param channel The channel of the digital input used with this counter
+ */
+void StopCounter(UINT32 channel)
+{
+ Counter *counter = AllocateCounter(channel);
+ if (counter != NULL)
+ counter->Stop();
+}
+
+/*
+ * Get the Period of the most recent count.
+ * Returns the time interval of the most recent count. This can be used for velocity calculations
+ * to determine shaft speed.
+ * @param slot The slot the digital module is plugged into
+ * @param channel The channel of the digital input used with this counter
+ * @returns The period of the last two pulses in units of seconds.
+ */
+double GetCounterPeriod(UINT8 moduleNumber, UINT32 channel)
+{
+ Counter *counter = AllocateCounter(moduleNumber, channel);
+ if (counter != NULL)
+ return counter->GetPeriod();
+ else
+ return 0;
+}
+
+/*
+ * Get the Period of the most recent count.
+ * Returns the time interval of the most recent count. This can be used for velocity calculations
+ * to determine shaft speed.
+ * @param channel The channel of the digital input used with this counter
+ * @returns The period of the last two pulses in units of seconds.
+ */
+double GetCounterPeriod(UINT32 channel)
+{
+ Counter *counter = AllocateCounter(channel);
+ if (counter != NULL)
+ return counter->GetPeriod();
+ else
+ return 0;
+}
+
+/**
+ * Delete the resources associated with this counter.
+ * The resources including the underlying object are deleted for this counter.
+ * @param slot The slot the digital module is plugged into
+ * @param channel The channel of the digital input used with this counter
+ */
+void DeleteCounter(UINT8 moduleNumber, UINT32 channel)
+{
+ if (SensorBase::CheckDigitalModule(moduleNumber) && SensorBase::CheckDigitalChannel(channel))
+ {
+ UINT32 slotOffset = moduleNumber - 1;
+ delete counters[slotOffset][channel - 1];
+ counters[slotOffset][channel - 1] = NULL;
+ }
+}
+
+/**
+ * Delete the resources associated with this counter.
+ * The resources including the underlying object are deleted for this counter.
+ * @param channel The channel of the digital input used with this counter
+ */
+void DeleteCounter(UINT32 channel)
+{
+ DeleteCounter(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+/*******************************************************************************
+ * Alternative interface to counter
+*******************************************************************************/
+
+CounterObject CreateCounter(UINT32 channel)
+{
+ return (CounterObject) new Counter(channel);
+}
+
+CounterObject CreateCounter(UINT8 moduleNumber, UINT32 channel)
+{
+ return (CounterObject) new Counter(moduleNumber,channel);
+}
+
+void StartCounter(CounterObject o)
+{
+ ((Counter *) o)->Start();
+}
+
+INT32 GetCounter(CounterObject o)
+{
+ return ((Counter *) o)->Get();
+}
+
+void ResetCounter(CounterObject o)
+{
+ ((Counter *) o)->Reset();
+}
+
+void StopCounter(CounterObject o)
+{
+ ((Counter *) o)->Stop();
+}
+
+double GetCounterPeriod(CounterObject o)
+{
+ return ((Counter *) o)->GetPeriod();
+}
+
+void DeleteCounter(CounterObject o)
+{
+ delete (Counter *) o;
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CCounter.h b/aos/externals/WPILib/WPILib/CInterfaces/CCounter.h
new file mode 100644
index 0000000..0a9fd22
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CCounter.h
@@ -0,0 +1,29 @@
+#ifndef _C_COUNTER_H
+#define _C_COUNTER_H
+
+void StartCounter(UINT32 channel);
+void StartCounter(UINT8 moduleNumber, UINT32 channel);
+INT32 GetCounter(UINT32 channel);
+INT32 GetCounter(UINT8 moduleNumber, UINT32 channel);
+void ResetCounter(UINT32 channel);
+void ResetCounter(UINT8 moduleNumber, UINT32 channel);
+void StopCounter(UINT32 channel);
+void StopCounter(UINT8 moduleNumber, UINT32 channel);
+double GetCounterPeriod(UINT32 channel);
+double GetCounterPeriod(UINT8 moduleNumber, UINT32 channel);
+void DeleteCounter(UINT32 channel);
+void DeleteCounter(UINT8 moduleNumber, UINT32 channel);
+
+typedef void *CounterObject;
+
+CounterObject CreateCounter(UINT32 channel);
+CounterObject CreateCounter(UINT8 moduleNumber, UINT32 channel);
+void StartCounter(CounterObject o);
+INT32 GetCounter(CounterObject o);
+void ResetCounter(CounterObject o);
+void StopCounter(CounterObject o);
+double GetCounterPeriod(CounterObject o);
+void DeleteCounter(CounterObject o);
+
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CDigitalInput.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CDigitalInput.cpp
new file mode 100644
index 0000000..88e19ef
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CDigitalInput.cpp
@@ -0,0 +1,121 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "DigitalModule.h"
+#include "DigitalInput.h"
+#include "CInterfaces/CDigitalInput.h"
+
+static DigitalInput* digitalInputs[SensorBase::kDigitalModules][SensorBase::kDigitalChannels];
+static bool initialized = false;
+
+/**
+ * Allocates the resources associated with a DigitalInput.
+ * Allocate the underlying DigitalInput object and the reservations for the
+ * associated slot and channel.
+ *
+ * @param slot The slot the digital input module is plugged into
+ * @param channel The particular channel this digital input is using
+ */
+static DigitalInput *AllocateDigitalInput(UINT8 moduleNumber, UINT32 channel)
+{
+ if (!initialized)
+ {
+ for (unsigned i = 0; i < SensorBase::kDigitalModules; i++)
+ for (unsigned j = 0; j < SensorBase::kDigitalChannels; j++)
+ digitalInputs[i][j] = NULL;
+ initialized = true;
+ }
+ if (SensorBase::CheckDigitalModule(moduleNumber) && SensorBase::CheckDigitalChannel(channel))
+ {
+ UINT32 slotOffset = moduleNumber - 1;
+ if (digitalInputs[slotOffset][channel - 1] == NULL)
+ {
+ digitalInputs[slotOffset][channel - 1] = new DigitalInput(moduleNumber, channel);
+ }
+ return digitalInputs[slotOffset][channel - 1];
+ }
+ return NULL;
+}
+
+/*
+ * Get the value from a digital input channel.
+ * Retrieve the value of a single digital input channel from the FPGA.
+ *
+ * @param slot The slot the digital input module is plugged into
+ * @param channel The particular channel this digital input is using
+ */
+UINT32 GetDigitalInput(UINT8 moduleNumber, UINT32 channel)
+{
+ DigitalInput *digIn = AllocateDigitalInput(moduleNumber, channel);
+ if (digIn)
+ return digIn->Get();
+ else
+ return 0;
+}
+
+/*
+ * Get the value from a digital input channel.
+ * Retrieve the value of a single digital input channel from the FPGA.
+ *
+ * @param channel The particular channel this digital input is using
+ */
+UINT32 GetDigitalInput(UINT32 channel)
+{
+ return GetDigitalInput(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+/**
+ * Frees the resources for this DigitalInput.
+ * Deletes the underlying object and frees the reservation for the associated digital
+ * input port.
+ *
+ * @param slot The slot the digital input module is plugged into
+ * @param channel The particular channel this digital input is using
+ */
+void DeleteDigitalInput(UINT8 moduleNumber, UINT32 channel)
+{
+ if (SensorBase::CheckDigitalModule(moduleNumber) && SensorBase::CheckDigitalChannel(channel))
+ {
+ UINT32 slotOffset = moduleNumber - 1;
+ delete digitalInputs[slotOffset][channel - 1];
+ digitalInputs[slotOffset][channel - 1] = NULL;
+ }
+}
+
+/**
+ * Frees the resources for this DigitalInput.
+ * Deletes the underlying object and frees the reservation for the associated digital
+ * input port.
+ *
+ * @param channel The particular channel this digital input is using
+ */
+void DeleteDigitalInput(UINT32 channel)
+{
+ DeleteDigitalInput(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+/*******************************************************************************
+ * Alternative interface to digital input
+*******************************************************************************/
+DigitalInputObject CreateDigitalInput(UINT8 moduleNumber, UINT32 channel)
+{
+ return (DigitalInputObject) new DigitalInput(moduleNumber, channel);
+}
+
+DigitalInputObject CreateDigitalInput(UINT32 channel)
+{
+ return (DigitalInputObject) new DigitalInput(channel);
+}
+
+bool GetDigitalInput(DigitalInputObject o)
+{
+ return ((DigitalInput *) o)->Get();
+}
+
+void DeleteDigitalInput(DigitalInputObject o)
+{
+ delete (DigitalInput *) o;
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CDigitalInput.h b/aos/externals/WPILib/WPILib/CInterfaces/CDigitalInput.h
new file mode 100644
index 0000000..185b173
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CDigitalInput.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef _C_DIGITAL_INPUT_H
+#define _C_DIGITIL_INPUT_H
+
+UINT32 GetDigitalInput(UINT8 moduleNumber, UINT32 channel);
+UINT32 GetDigitalInput(UINT32 channel);
+void DeleteDigitalInput(UINT8 moduleNumber, UINT32 channel);
+void DeleteDigitalInput(UINT32 channel);
+
+typedef void *DigitalInputObject;
+
+DigitalInputObject CreateDigitalInput(UINT8 moduleNumber, UINT32 channel);
+DigitalInputObject CreateDigitalInput(UINT32 channel);
+bool GetDigitalInput(DigitalInputObject o);
+void DeleteDigitalInput(DigitalInputObject o);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CDigitalOutput.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CDigitalOutput.cpp
new file mode 100644
index 0000000..acbec96
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CDigitalOutput.cpp
@@ -0,0 +1,123 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "DigitalModule.h"
+#include "DigitalOutput.h"
+#include "CInterfaces/CDigitalOutput.h"
+
+static DigitalOutput* digitalOutputs[SensorBase::kDigitalModules][SensorBase::kDigitalChannels];
+static bool initialized = false;
+
+/**
+ * Allocate the DigitalOuput.
+ * Allocates the resources associated with this DigitalOutput including the channel/slot reservation
+ * and the underlying DigitalOutput object.
+ *
+ * @param slot The slot this digital module is plugged into
+ * @param channel The channel being used for this digital output
+ */
+static DigitalOutput * AllocateDigitalOutput(UINT8 moduleNumber, UINT32 channel)
+{
+ if (!initialized)
+ {
+ for (unsigned i = 0; i < SensorBase::kDigitalModules; i++)
+ for (unsigned j = 0; j < SensorBase::kDigitalChannels; j++)
+ digitalOutputs[i][j] = NULL;
+ initialized = true;
+ }
+ if (SensorBase::CheckDigitalModule(moduleNumber) && SensorBase::CheckDigitalChannel(channel))
+ {
+ unsigned slotOffset = moduleNumber - 1;
+ if (digitalOutputs[slotOffset][channel - 1] == NULL)
+ {
+ digitalOutputs[slotOffset][channel - 1] = new DigitalOutput(moduleNumber, channel);
+ }
+ return digitalOutputs[slotOffset][channel - 1];
+ }
+ return NULL;
+}
+
+/**
+ * Set the value of a digital output.
+ * Set the value of a digital output to either one (true) or zero (false).
+ *
+ * @param slot The slot this digital module is plugged into
+ * @param channel The channel being used for this digital output
+ * @param value The 0/1 value set to the port.
+ */
+void SetDigitalOutput(UINT8 moduleNumber, UINT32 channel, UINT32 value)
+{
+ DigitalOutput *digOut = AllocateDigitalOutput(moduleNumber, channel);
+ if (digOut)
+ digOut->Set(value);
+}
+
+/**
+ * Set the value of a digital output.
+ * Set the value of a digital output to either one (true) or zero (false).
+ *
+ * @param channel The channel being used for this digital output
+ * @param value The 0/1 value set to the port.
+ */
+void SetDigitalOutput(UINT32 channel, UINT32 value)
+{
+ SetDigitalOutput(SensorBase::GetDefaultDigitalModule(), channel, value);
+}
+
+/**
+ * Free the resources associated with this digital output.
+ * The underlying DigitalOutput object and the resouces for the channel and slot are
+ * freed so they can be reused.
+ *
+ * @param slot The slot this digital module is plugged into
+ * @param channel The channel being used for this digital output
+ */
+void DeleteDigitalOutput(UINT8 moduleNumber, UINT32 channel)
+{
+ if (SensorBase::CheckDigitalModule(moduleNumber) && SensorBase::CheckDigitalChannel(channel))
+ {
+ unsigned slotOffset = moduleNumber - 1;
+ delete digitalOutputs[slotOffset][channel - 1];
+ digitalOutputs[slotOffset][channel - 1] = NULL;
+ }
+}
+
+/**
+ * Free the resources associated with this digital output.
+ * The underlying DigitalOutput object and the resouces for the channel and slot are
+ * freed so they can be reused.
+ *
+ * @param channel The channel being used for this digital output
+ */
+void DeleteDigitalOutput(UINT32 channel)
+{
+ DeleteDigitalOutput(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+/*******************************************************************************
+ * Alternative interface to digital output
+*******************************************************************************/
+DigitalOutputObject CreateDigitalOutput(UINT8 moduleNumber, UINT32 channel)
+{
+ return (DigitalOutputObject) new DigitalOutput(moduleNumber, channel);
+}
+
+DigitalOutputObject CreateDigitalOutput(UINT32 channel)
+{
+ return (DigitalOutputObject) new DigitalOutput(channel);
+}
+
+void SetDigitalOutput(DigitalOutputObject o, bool val)
+{
+ ((DigitalOutput *) o)->Set(val);
+}
+
+void DeleteDigitalOutput(DigitalOutputObject o)
+{
+ delete (DigitalOutput *) o;
+}
+
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CDigitalOutput.h b/aos/externals/WPILib/WPILib/CInterfaces/CDigitalOutput.h
new file mode 100644
index 0000000..22c5915
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CDigitalOutput.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef _C_DIGITAL_OUTPUT_H
+#define _C_DIGITIL_OUTPUT_H
+
+void SetDigitalOutput(UINT8 moduleNumber, UINT32 channel, UINT32 value);
+void SetDigitalOutput(UINT32 channel, UINT32 value);
+void DeleteDigitalOutput(UINT8 moduleNumber, UINT32 channel);
+void DeleteDigitalOutput(UINT32 channel);
+
+typedef void *DigitalOutputObject;
+
+DigitalOutputObject CreateDigitalOutput(UINT8 moduleNumber, UINT32 channel);
+DigitalOutputObject CreateDigitalOutput(UINT32 channel);
+void SetDigitalOutput(DigitalOutputObject o, bool val);
+void DeleteDigitalOutput(DigitalOutputObject o);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CDriverStation.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CDriverStation.cpp
new file mode 100644
index 0000000..0cd0313
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CDriverStation.cpp
@@ -0,0 +1,153 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "DriverStation.h"
+#include "CInterfaces/CDriverStation.h"
+
+static DriverStation *ds = NULL;
+
+/**
+ * Get the value of the axis on a joystick.
+ * This depends on the mapping of the joystick connected to the specified port.
+ *
+ * @param stick The joystick to read.
+ * @param axis The analog axis value to read from the joystick.
+ * @return The value of the axis on the joystick.
+ */
+float GetStickAxis(UINT32 stick, UINT32 axis)
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->GetStickAxis(stick, axis);
+}
+
+/**
+ * The state of the buttons on the joystick.
+ * 12 buttons (4 msb are unused) from the joystick.
+ *
+ * @param stick The joystick to read.
+ * @return The state of the buttons on the joystick.
+ */
+short GetStickButtons(UINT32 stick)
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->GetStickButtons(stick);
+}
+
+/**
+ * Get an analog voltage from the Driver Station.
+ * The analog values are returned as UINT32 values for the Driver Station analog inputs.
+ * These inputs are typically used for advanced operator interfaces consisting of potentiometers
+ * or resistor networks representing values on a rotary switch.
+ *
+ * @param channel The analog input channel on the driver station to read from. Valid range is 1 - 4.
+ * @return The analog voltage on the input.
+ */
+float GetAnalogIn(UINT32 channel)
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->GetAnalogIn(channel);
+}
+
+/**
+ * Get values from the digital inputs on the Driver Station.
+ * Return digital values from the Drivers Station. These values are typically used for buttons
+ * and switches on advanced operator interfaces.
+ * @param channel The digital input to get. Valid range is 1 - 8.
+ */
+bool GetDigitalIn(UINT32 channel)
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->GetDigitalIn(channel);
+}
+
+/**
+ * Set a value for the digital outputs on the Driver Station.
+ *
+ * Control digital outputs on the Drivers Station. These values are typically used for
+ * giving feedback on a custom operator station such as LEDs.
+ *
+ * @param channel The digital output to set. Valid range is 1 - 8.
+ * @param value The state to set the digital output.
+ */
+void SetDigitalOut(UINT32 channel, bool value)
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ ds->SetDigitalOut(channel, value);
+}
+
+/**
+ * Get a value that was set for the digital outputs on the Driver Station.
+ * @param channel The digital ouput to monitor. Valid range is 1 through 8.
+ * @return A digital value being output on the Drivers Station.
+ */
+bool GetDigitalOut(UINT32 channel)
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->GetDigitalOut(channel);
+}
+
+/**
+ * Returns the robot state
+ * @returns true if the robot is disabled
+ */
+bool IsDisabled()
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->IsDisabled();
+}
+
+/**
+ * Returns flag for field state
+ * @returns true if the field is in Autonomous mode
+ */
+bool IsAutonomous()
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->IsAutonomous();
+}
+
+/**
+ * Returns flag for field state
+ * @returns true if the field is in Operator Control mode (teleop)
+ */
+bool IsOperatorControl()
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->IsOperatorControl();
+}
+
+/**
+ * Return the DS packet number.
+ * The packet number is the index of this set of data returned by the driver station.
+ * Each time new data is received, the packet number (included with the sent data) is returned.
+ */
+UINT32 GetPacketNumber()
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->GetPacketNumber();
+}
+
+UINT32 GetAlliance()
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->GetAlliance();
+}
+
+UINT32 GetLocation()
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->GetLocation();
+}
+
+/**
+ * Get the battery voltage on the robot
+ * @returns the battery voltage in volts
+ */
+float GetBatteryVoltage()
+{
+ if (ds == NULL) ds = DriverStation::GetInstance();
+ return ds->GetBatteryVoltage();
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CDriverStation.h b/aos/externals/WPILib/WPILib/CInterfaces/CDriverStation.h
new file mode 100644
index 0000000..dbd828e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CDriverStation.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef _C_DRIVER_STATION_H
+#define _C_DRIVER_STATION_H
+
+float GetStickAxis(UINT32 stick, UINT32 axis);
+short GetStickButtons(UINT32 stick);
+
+float GetAnalogIn(UINT32 channel);
+bool GetDigitalIn(UINT32 channel);
+void SetDigitalOut(UINT32 channel, bool value);
+bool GetDigitalOut(UINT32 channel);
+
+bool IsDisabled();
+bool IsAutonomous();
+bool IsOperatorControl();
+
+UINT32 GetPacketNumber();
+UINT32 GetAlliance();
+UINT32 GetLocation();
+
+float GetBatteryVoltage();
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CEncoder.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CEncoder.cpp
new file mode 100644
index 0000000..7e9eb3b
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CEncoder.cpp
@@ -0,0 +1,674 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Encoder.h"
+#include "SensorBase.h"
+#include "DigitalModule.h"
+#include "CInterfaces/CEncoder.h"
+
+static Encoder* encoders[SensorBase::kDigitalModules][SensorBase::kDigitalChannels];
+static bool initialized = false;
+
+/**
+ * Allocate the resources associated with this encoder.
+ * Allocate an Encoder object and cache the value in the associated table to find it
+ * in the future.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+static Encoder *AllocateEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ Encoder *encoder;
+ if (!initialized)
+ {
+ for (unsigned slot = 0; slot < SensorBase::kDigitalModules; slot++)
+ for (unsigned channel = 0; channel < SensorBase::kDigitalChannels; channel++)
+ encoders[slot][channel] = NULL;
+ initialized = true;
+ }
+ // check if the channel and slots are valid values
+ if (!SensorBase::CheckDigitalModule(amoduleNumber)
+ || !SensorBase::CheckDigitalChannel(aChannel)
+ || !SensorBase::CheckDigitalModule(bmoduleNumber)
+ || !SensorBase::CheckDigitalChannel(bChannel)) return NULL;
+ // check if nothing has been allocated to that pair of channels
+ if (encoders[amoduleNumber - 1][aChannel - 1] == NULL
+ && encoders[bmoduleNumber - 1][bChannel - 1] == NULL)
+ {
+ // allocate an encoder and put it into both slots
+ encoder = new Encoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ encoders[amoduleNumber - 1][aChannel - 1] = encoder;
+ encoders[bmoduleNumber - 1][bChannel - 1] = encoder;
+ return encoder;
+ }
+ // if there was the same encoder object allocated to both channels, return it
+ if ((encoder = encoders[amoduleNumber - 1][aChannel - 1]) ==
+ encoders[bmoduleNumber - 1][bChannel - 1])
+ return encoder;
+ // Otherwise, one of the channels is allocated and the other isn't, so this is a
+ // resource allocation error.
+ return NULL;
+}
+
+/**
+ * Allocate the resources associated with this encoder.
+ * Allocate an Encoder object and cache the value in the associated table to find it
+ * in the future.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+static Encoder *AllocateEncoder(UINT32 aChannel, UINT32 bChannel)
+{
+ return AllocateEncoder(SensorBase::GetDefaultDigitalModule(), aChannel,
+ SensorBase::GetDefaultDigitalModule(), bChannel);
+}
+
+/**
+ * Start the encoder counting.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void StartEncoder(UINT32 aChannel, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ {
+ encoder->Start();
+ }
+}
+
+/**
+ * Start the encoder counting.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void StartEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ {
+ encoder->Start();
+ }
+}
+
+/**
+ * Gets the current count.
+ * Returns the current count on the Encoder.
+ * This method compensates for the decoding type.
+ *
+ * @deprecated Use GetEncoderDistance() in favor of this method. This returns unscaled pulses and GetDistance() scales using value from SetEncoderDistancePerPulse().
+ *
+ * @return Current count from the Encoder.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+INT32 GetEncoder(UINT32 aChannel, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ return encoder->Get();
+ else
+ return 0;
+}
+
+/**
+ * Gets the current count.
+ * Returns the current count on the Encoder.
+ * This method compensates for the decoding type.
+ *
+ * @deprecated Use GetEncoderDistance() in favor of this method. This returns unscaled pulses and GetDistance() scales using value from SetEncoderDistancePerPulse().
+ *
+ * @return Current count from the Encoder.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+INT32 GetEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, amoduleNumber, bChannel);
+ if (encoder != NULL)
+ return encoder->Get();
+ else
+ return 0;
+}
+
+/**
+ * Reset the count for the encoder object.
+ * Resets the count to zero.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void ResetEncoder(UINT32 aChannel, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ encoder->Reset();
+}
+
+/**
+ * Reset the count for the encoder object.
+ * Resets the count to zero.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void ResetEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ encoder->Reset();
+}
+
+/**
+ * Stops the counting for the encoder object.
+ * Stops the counting for the Encoder. It still retains the count, but it doesn't change
+ * with pulses until it is started again.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void StopEncoder(UINT32 aChannel, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ encoder->Stop();
+}
+
+/**
+ * Stops the counting for the encoder object.
+ * Stops the counting for the Encoder. It still retains the count, but it doesn't change
+ * with pulses until it is started again.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void StopEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ encoder->Stop();
+}
+
+/**
+ * Returns the period of the most recent pulse.
+ * Returns the period of the most recent Encoder pulse in seconds.
+ * This method compenstates for the decoding type.
+ *
+ * @deprecated Use GetEncoderRate() in favor of this method. This returns unscaled periods and GetEncoderRate() scales using value from SetEncoderDistancePerPulse().
+ *
+ * @return Period in seconds of the most recent pulse.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+double GetEncoderPeriod(UINT32 aChannel, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ return encoder->GetPeriod();
+ else
+ return 0.0;
+}
+
+/**
+ * Returns the period of the most recent pulse.
+ * Returns the period of the most recent Encoder pulse in seconds.
+ * This method compenstates for the decoding type.
+ *
+ * @deprecated Use GetEncoderRate() in favor of this method. This returns unscaled periods and GetEncoderRate() scales using value from SetEncoderDistancePerPulse().
+ *
+ * @return Period in seconds of the most recent pulse.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+double GetEncoderPeriod(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ return encoder->GetPeriod();
+ else
+ return 0.0;
+}
+
+
+/**
+ * Sets the maximum period for stopped detection.
+ * Sets the value that represents the maximum period of the Encoder before it will assume
+ * that the attached device is stopped. This timeout allows users to determine if the wheels or
+ * other shaft has stopped rotating.
+ * This method compensates for the decoding type.
+ *
+ * @deprecated Use SetEncoderMinRate() in favor of this method. This takes unscaled periods and SetMinEncoderRate() scales using value from SetEncoderDistancePerPulse().
+ *
+ * @param maxPeriod The maximum time between rising and falling edges before the FPGA will
+ * report the device stopped. This is expressed in seconds.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void SetMaxEncoderPeriod(UINT32 aChannel, UINT32 bChannel, double maxPeriod)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ encoder->SetMaxPeriod(maxPeriod);
+}
+
+/**
+ * Sets the maximum period for stopped detection.
+ * Sets the value that represents the maximum period of the Encoder before it will assume
+ * that the attached device is stopped. This timeout allows users to determine if the wheels or
+ * other shaft has stopped rotating.
+ * This method compensates for the decoding type.
+ *
+ * @deprecated Use SetEncoderMinRate() in favor of this method. This takes unscaled periods and SetMinEncoderRate() scales using value from SetEncoderDistancePerPulse().
+ *
+ * @param maxPeriod The maximum time between rising and falling edges before the FPGA will
+ * report the device stopped. This is expressed in seconds.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void SetMaxEncoderPeriod(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel, double maxPeriod)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ encoder->SetMaxPeriod(maxPeriod);
+}
+
+/**
+ * Determine if the encoder is stopped.
+ * Using the MaxPeriod value, a boolean is returned that is true if the encoder is considered
+ * stopped and false if it is still moving. A stopped encoder is one where the most recent pulse
+ * width exceeds the MaxPeriod.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ * @return True if the encoder is considered stopped.
+ */
+bool GetEncoderStopped(UINT32 aChannel, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ return encoder->GetStopped();
+ else
+ return false;
+}
+
+/**
+ * Determine if the encoder is stopped.
+ * Using the MaxPeriod value, a boolean is returned that is true if the encoder is considered
+ * stopped and false if it is still moving. A stopped encoder is one where the most recent pulse
+ * width exceeds the MaxPeriod.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ * @return True if the encoder is considered stopped.
+ */
+bool GetEncoderStopped(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ return encoder->GetStopped();
+ else
+ return false;
+}
+
+/**
+ * The last direction the encoder value changed.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ * @return The last direction the encoder value changed.
+ */
+bool GetEncoderDirection(UINT32 aChannel, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ return encoder->GetDirection();
+ else
+ return false;
+}
+
+/**
+ * The last direction the encoder value changed.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ * @return The last direction the encoder value changed.
+ */
+bool GetEncoderDirection(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ return encoder->GetDirection();
+ else
+ return false;
+}
+
+/**
+ * Get the distance the robot has driven since the last reset.
+ *
+ * @return The distance driven since the last reset as scaled by the value from SetEncoderDistancePerPulse().
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+double GetEncoderDistance(UINT32 aChannel, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ return encoder->GetDistance();
+ else
+ return 0.0;
+}
+
+/**
+ * Get the distance the robot has driven since the last reset.
+ *
+ * @return The distance driven since the last reset as scaled by the value from SetEncoderDistancePerPulse().
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+double GetEncoderDistance(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ return encoder->GetDistance();
+ else
+ return 0.0;
+}
+
+/**
+ * Get the current rate of the encoder.
+ * Units are distance per second as scaled by the value from SetEncoderDistancePerPulse().
+ *
+ * @return The current rate of the encoder.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+double GetEncoderRate(UINT32 aChannel, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ return encoder->GetRate();
+ else
+ return 0.0;
+}
+
+/**
+ * Get the current rate of the encoder.
+ * Units are distance per second as scaled by the value from SetEncoderDistancePerPulse().
+ *
+ * @return The current rate of the encoder.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+double GetEncoderRate(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ return encoder->GetRate();
+ else
+ return 0.0;
+}
+
+/**
+ * Set the minimum rate of the device before the hardware reports it stopped.
+ *
+ * @param minRate The minimum rate. The units are in distance per second as scaled by the value from SetEncoderDistancePerPulse().
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void SetMinEncoderRate(UINT32 aChannel, UINT32 bChannel, double minRate)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ encoder->SetMinRate(minRate);
+}
+
+/**
+ * Set the minimum rate of the device before the hardware reports it stopped.
+ *
+ * @param minRate The minimum rate. The units are in distance per second as scaled by the value from SetEncoderDistancePerPulse().
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void SetMinEncoderRate(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel, double minRate)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ encoder->SetMinRate(minRate);
+}
+
+/**
+ * Set the distance per pulse for this encoder.
+ * This sets the multiplier used to determine the distance driven based on the count value
+ * from the encoder.
+ * Do not include the decoding type in this scale. The library already compensates for the decoding type.
+ * Set this value based on the encoder's rated Pulses per Revolution and
+ * factor in gearing reductions following the encoder shaft.
+ * This distance can be in any units you like, linear or angular.
+ *
+ * @param distancePerPulse The scale factor that will be used to convert pulses to useful units.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void SetEncoderDistancePerPulse(UINT32 aChannel, UINT32 bChannel, double distancePerPulse)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ encoder->SetDistancePerPulse(distancePerPulse);
+}
+
+/**
+ * Set the distance per pulse for this encoder.
+ * This sets the multiplier used to determine the distance driven based on the count value
+ * from the encoder.
+ * Do not include the decoding type in this scale. The library already compensates for the decoding type.
+ * Set this value based on the encoder's rated Pulses per Revolution and
+ * factor in gearing reductions following the encoder shaft.
+ * This distance can be in any units you like, linear or angular.
+ *
+ * @param distancePerPulse The scale factor that will be used to convert pulses to useful units.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void SetEncoderDistancePerPulse(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel, double distancePerPulse)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ encoder->SetDistancePerPulse(distancePerPulse);
+}
+
+/**
+ * Set the direction sensing for this encoder.
+ * This sets the direction sensing on the encoder so that it could count in the correct
+ * software direction regardless of the mounting.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ * @param reverseDirection true if the encoder direction should be reversed
+ */
+void SetEncoderReverseDirection(UINT32 aChannel, UINT32 bChannel, bool reverseDirection)
+{
+ Encoder *encoder = AllocateEncoder(aChannel, bChannel);
+ if (encoder != NULL)
+ encoder->SetReverseDirection(reverseDirection);
+}
+
+/**
+ * Set the direction sensing for this encoder.
+ * This sets the direction sensing on the encoder so that it couldl count in the correct
+ * software direction regardless of the mounting.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ * @param reverseDirection true if the encoder direction should be reversed
+ */
+void SetEncoderReverseDirection(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel, bool reverseDirection)
+{
+ Encoder *encoder = AllocateEncoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+ if (encoder != NULL)
+ encoder->SetReverseDirection(reverseDirection);
+}
+
+/**
+ * Free the resources associated with this encoder.
+ * Delete the Encoder object and the entries from the cache for this encoder.
+ *
+ * @param aSlot The digital module slot for the A Channel on the encoder
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bSlot The digital module slot for the B Channel on the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void DeleteEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ if (SensorBase::CheckDigitalModule(amoduleNumber) && SensorBase::CheckDigitalChannel(aChannel) &&
+ SensorBase::CheckDigitalModule(bmoduleNumber) && SensorBase::CheckDigitalChannel(bChannel))
+ {
+ delete encoders[amoduleNumber - 1][aChannel - 1];
+ encoders[amoduleNumber - 1][aChannel - 1] = NULL;
+ encoders[bmoduleNumber - 1][bChannel - 1] = NULL;
+ }
+}
+
+/**
+ * Free the resources associated with this encoder.
+ * Delete the Encoder object and the entries from the cache for this encoder.
+ *
+ * @param aChannel The channel on the digital module for the A Channel of the encoder
+ * @param bChannel The channel on the digital module for the B Channel of the encoder
+ */
+void DeleteEncoder(UINT32 aChannel, UINT32 bChannel)
+{
+ DeleteEncoder(SensorBase::GetDefaultDigitalModule(), aChannel, SensorBase::GetDefaultDigitalModule(), bChannel);
+}
+
+/**
+ * Alternate C Interface
+ */
+
+EncoderObject CreateEncoder(UINT32 aChannel, UINT32 bChannel)
+{
+ return (EncoderObject) new Encoder(aChannel, bChannel);
+}
+
+EncoderObject CreateEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel)
+{
+ return (EncoderObject) new Encoder(amoduleNumber, aChannel, bmoduleNumber, bChannel);
+}
+
+void StartEncoder(EncoderObject o)
+{
+ ((Encoder *)o )->Start();
+}
+
+INT32 GetEncoder(EncoderObject o)
+{
+ return ((Encoder *)o )->Get();
+}
+
+void ResetEncoder(EncoderObject o)
+{
+ ((Encoder *)o )->Reset();
+}
+
+void StopEncoder(EncoderObject o)
+{
+ ((Encoder *)o )->Stop();
+}
+
+double GetEncoderPeriod(EncoderObject o)
+{
+ return ((Encoder *)o )->GetPeriod();
+}
+
+void SetMaxEncoderPeriod(EncoderObject o, double maxPeriod)
+{
+ ((Encoder *)o )->SetMaxPeriod(maxPeriod);
+}
+
+bool GetEncoderStopped(EncoderObject o)
+{
+ return ((Encoder *)o )->GetStopped();
+}
+
+bool GetEncoderDirection(EncoderObject o)
+{
+ return ((Encoder *)o )->GetDirection();
+}
+
+double GetEncoderDistance(EncoderObject o)
+{
+ return ((Encoder *)o )->GetDistance();
+}
+
+double GetEncoderRate(EncoderObject o)
+{
+ return ((Encoder *)o )->GetRate();
+}
+
+void SetMinEncoderRate(EncoderObject o, double minRate)
+{
+ ((Encoder *)o )->SetMinRate(minRate);
+}
+
+void SetEncoderDistancePerPulse(EncoderObject o, double distancePerPulse)
+{
+ ((Encoder *)o )->SetDistancePerPulse(distancePerPulse);
+}
+
+void SetEncoderReverseDirection(EncoderObject o, bool reversedDirection)
+{
+ ((Encoder *)o )->SetReverseDirection(reversedDirection);
+}
+
+void DeleteEncoder(EncoderObject o)
+{
+ delete (Encoder *)o;
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CEncoder.h b/aos/externals/WPILib/WPILib/CInterfaces/CEncoder.h
new file mode 100644
index 0000000..040ea7e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CEncoder.h
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef _C_ENCODER_H
+#define _C_ENCODER_H
+
+void StartEncoder(UINT32 aChannel, UINT32 bChannel);
+INT32 GetEncoder(UINT32 aChannel, UINT32 bChannel);
+void ResetEncoder(UINT32 aChannel, UINT32 bChannel);
+void StopEncoder(UINT32 aChannel, UINT32 bChannel);
+double GetEncoderPeriod(UINT32 aChannel, UINT32 bChannel);
+void SetMaxEncoderPeriod(UINT32 aChannel, UINT32 bChannel, double maxPeriod);
+bool GetEncoderStopped(UINT32 aChannel, UINT32 bChannel);
+bool GetEncoderDirection(UINT32 aChannel, UINT32 bChannel);
+double GetEncoderDistance(UINT32 aChannel, UINT32 bChannel);
+double GetEncoderRate(UINT32 aChannel, UINT32 bChannel);
+void SetMinEncoderRate(UINT32 aChannel, UINT32 bChannel, double minRate);
+void SetEncoderDistancePerPulse(UINT32 aChannel, UINT32 bChannel, double distancePerPulse);
+void SetEncoderReverseDirection(UINT32 aChannel, UINT32 bChannel, bool reversedDirection);
+void StartEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel);
+INT32 GetEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel);
+void ResetEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel);
+void StopEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel);
+double GetEncoderPeriod(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel);
+void SetMaxEncoderPeriod(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel, double maxPeriod);
+bool GetEncoderStopped(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel);
+bool GetEncoderDirection(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel);
+double GetEncoderDistance(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel);
+double GetEncoderRate(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel);
+void SetMinEncoderRate(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel, double minRate);
+void SetEncoderDistancePerPulse(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel, double distancePerPulse);
+void SetEncoderReverseDirection(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel, bool reversedDirection);
+void DeleteEncoder(UINT32 aChannel, UINT32 bChannel);
+void DeleteEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel);
+
+typedef void *EncoderObject;
+
+EncoderObject CreateEncoder(UINT32 aChannel, UINT32 bChannel);
+EncoderObject CreateEncoder(UINT8 amoduleNumber, UINT32 aChannel, UINT8 bmoduleNumber, UINT32 bChannel);
+void StartEncoder(EncoderObject o);
+INT32 GetEncoder(EncoderObject o);
+void ResetEncoder(EncoderObject o);
+void StopEncoder(EncoderObject o);
+double GetEncoderPeriod(EncoderObject o);
+void SetMaxEncoderPeriod(EncoderObject o, double maxPeriod);
+bool GetEncoderStopped(EncoderObject o);
+bool GetEncoderDirection(EncoderObject o);
+double GetEncoderDistance(EncoderObject o);
+double GetEncoderRate(EncoderObject o);
+void SetMinEncoderRate(EncoderObject o, double minRate);
+void SetEncoderDistancePerPulse(EncoderObject o, double distancePerPulse);
+void SetEncoderReverseDirection(EncoderObject o, bool reversedDirection);
+void DeleteEncoder(EncoderObject o);
+#endif
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CError.h b/aos/externals/WPILib/WPILib/CInterfaces/CError.h
new file mode 100644
index 0000000..d98d273
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CError.h
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef C_ERROR_H
+#define C_ERROR_H
+
+#include "ErrorBase.h"
+#include <VxWorks.h>
+
+class CError : public ErrorBase
+{
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CGearTooth.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CGearTooth.cpp
new file mode 100644
index 0000000..5fb30ff
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CGearTooth.cpp
@@ -0,0 +1,236 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#include "CInterfaces/CGearTooth.h"
+#include "DigitalModule.h"
+
+static GearTooth* gearToothSensors[SensorBase::kChassisSlots][SensorBase::kDigitalChannels];
+static bool initialized = false;
+
+/**
+ * Get a pointer to the gear tooth sensor given a slot and a channel.
+ * This is an internal routine to allocate (if necessary) a gear tooth
+ * object from inputs.
+ * @param slot The slot the GearTooth sensor is plugged into.
+ * @param channel The channel the GearTooth sensor is plugged into.
+ */
+static GearTooth *GTptr(UINT8 moduleNumber, UINT32 channel)
+{
+ if (!initialized)
+ {
+ initialized = true;
+ for (unsigned i = 0; i < SensorBase::kChassisSlots; i++)
+ for (unsigned j = 0; j < SensorBase::kDigitalChannels; j++)
+ gearToothSensors[i][j] = NULL;
+ }
+ GearTooth *gt = NULL;
+ if (SensorBase::CheckDigitalModule(moduleNumber) && SensorBase::CheckDigitalChannel(channel))
+ {
+ UINT32 slotIndex = moduleNumber - 1;
+ gt = gearToothSensors[slotIndex][channel - 1];
+ if (gt == NULL)
+ {
+ gt = new GearTooth(moduleNumber, channel);
+ gearToothSensors[slotIndex][channel - 1] = gt;
+ }
+ }
+ return gt;
+}
+
+/**
+ * Initialize the gear tooth sensor.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The digital I/O channel the sensor is plugged into
+ * @param directionSensitive True if this geartooth sensor can differentiate between
+ * foward and backward movement.
+ */
+void InitGearTooth(UINT8 moduleNumber, UINT32 channel, bool directionSensitive)
+{
+ GearTooth *gt = GTptr(moduleNumber, channel);
+ if (gt) gt->EnableDirectionSensing(directionSensitive);
+}
+
+/**
+ * Initialize the gear tooth sensor.
+ *
+ * @param channel The digital I/O channel the sensor is plugged into
+ * @param directionSensitive True if this geartooth sensor can differentiate between
+ * foward and backward movement.
+ */
+void InitGearTooth(UINT32 channel, bool directionSensitive)
+{
+ InitGearTooth(SensorBase::GetDefaultDigitalModule(), channel, directionSensitive);
+}
+
+/**
+ * Start the GearTooth sensor counting.
+ * Start the counting for the geartooth sensor. Before this, the sensor is allocated
+ * but not counting pulses.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The digital I/O channel the sensor is plugged into
+ */
+void StartGearTooth(UINT8 moduleNumber, UINT32 channel)
+{
+ GearTooth *gt = GTptr(moduleNumber, channel);
+ if (gt) gt->Start();
+}
+
+/**
+ * Start the GearTooth sensor counting.
+ * Start the counting for the geartooth sensor. Before this, the sensor is allocated
+ * but not counting pulses.
+ *
+ * @param channel The digital I/O channel the sensor is plugged into
+ */
+void StartGearTooth(UINT32 channel)
+{
+ StartGearTooth(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+/**
+ * Stop the gear tooth sensor from counting.
+ * The counting is disabled on the underlying Counter object.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The digital I/O channel the sensor is plugged into
+ */
+void StopGearTooth(UINT8 moduleNumber, UINT32 channel)
+{
+ GearTooth *gt = GTptr(moduleNumber, channel);
+ if (gt) gt->Stop();
+}
+
+/**
+ * Stop the gear tooth sensor from counting.
+ * The counting is disabled on the underlying Counter object.
+ *
+ * @param channel The digital I/O channel the sensor is plugged into
+ */
+void StopGearTooth(UINT32 channel)
+{
+ StopGearTooth(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+/**
+ * Get value from GearTooth sensor.
+ * Get the current count from the sensor.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The digital I/O channel the sensor is plugged into
+ */
+INT32 GetGearTooth(UINT8 moduleNumber, UINT32 channel)
+{
+ GearTooth *gt = GTptr(moduleNumber, channel);
+ if (gt) return gt->Get();
+ return 0;
+}
+
+/**
+ * Get value from GearTooth sensor.
+ * Get the current count from the sensor.
+ *
+ * @param channel The digital I/O channel the sensor is plugged into
+ */
+INT32 GetGearTooth(UINT32 channel)
+{
+ return GetGearTooth(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+/**
+ * Reset the GearTooth sensor.
+ * Reset the count to zero for the gear tooth sensor.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The digital I/O channel the sensor is plugged into
+ */
+void ResetGearTooth(UINT8 moduleNumber, UINT32 channel)
+{
+ GearTooth *gt = GTptr(moduleNumber, channel);
+ if (gt) gt->Reset();
+}
+
+/**
+ * Reset the GearTooth sensor.
+ * Reset the count to zero for the gear tooth sensor.
+ *
+ * @param channel The digital I/O channel the sensor is plugged into
+ */
+void ResetGearTooth(UINT32 channel)
+{
+ ResetGearTooth(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+/**
+ * Free the resources associated with this gear tooth sensor.
+ * Delete the underlying object and free the resources for this geartooth
+ * sensor.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The digital I/O channel the sensor is plugged into
+ */
+void DeleteGearTooth(UINT8 moduleNumber, UINT32 channel)
+{
+ if (SensorBase::CheckDigitalModule(moduleNumber) && SensorBase::CheckDigitalChannel(channel))
+ {
+ UINT32 slotIndex = moduleNumber - 1;
+ delete gearToothSensors[slotIndex][channel - 1];
+ gearToothSensors[slotIndex][channel - 1] = NULL;
+ }
+}
+
+/**
+ * Free the resources associated with this gear tooth sensor.
+ * Delete the underlying object and free the resources for this geartooth
+ * sensor.
+ *
+ * @param channel The digital I/O channel the sensor is plugged into
+ */
+void DeleteGearTooth(UINT32 channel)
+{
+ DeleteGearTooth(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+
+/**
+ * Alternate C Interface
+ */
+
+GearToothObject CreateGearTooth(UINT32 channel, bool directionSensitive)
+{
+ return (GearToothObject) new GearTooth(channel, directionSensitive);
+}
+
+GearToothObject CreateGearTooth(UINT8 moduleNumber, UINT32 channel, bool directionSensitive)
+{
+ return (GearToothObject) new GearTooth(moduleNumber, channel, directionSensitive);
+}
+
+void StartGearTooth(GearToothObject o)
+{
+ ((GearTooth *)o )->Start();
+}
+
+void StopGearTooth(GearToothObject o)
+{
+ ((GearTooth *)o )->Stop();
+}
+
+INT32 GetGearTooth(GearToothObject o)
+{
+ return ((GearTooth *)o )->Get();
+}
+
+void ResetGearTooth(GearToothObject o)
+{
+ ((GearTooth *)o )->Reset();
+}
+
+void DeleteGearTooth(GearToothObject o)
+{
+ delete (GearTooth *)o;
+}
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CGearTooth.h b/aos/externals/WPILib/WPILib/CInterfaces/CGearTooth.h
new file mode 100644
index 0000000..998bbf4
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CGearTooth.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#ifndef C_GEARTOOTH_H
+#define C_GEARTOOTH_H
+
+#include "GearTooth.h"
+
+// TODO: Need to add support for digital sensors
+
+void InitGearTooth(UINT32 channel, bool directionSensitive);
+void InitGearTooth(UINT8 moduleNumber, UINT32 channel, bool directionSensitive);
+void StartGearTooth(UINT32 channel);
+void StartGearTooth(UINT8 moduleNumber, UINT32 channel);
+void StopGearTooth(UINT32 channel);
+void StopGearTooth(UINT8 moduleNumber, UINT32 channel);
+INT32 GetGearTooth(UINT32 channel);
+INT32 GetGearTooth(UINT8 moduleNumber, UINT32 channel);
+void ResetGearTooth(UINT32 channel);
+void ResetGearTooth(UINT8 moduleNumber, UINT32 channel);
+void DeleteGearTooth(UINT32 channel);
+void DeleteGearTooth(UINT8 moduleNumber, UINT32 channel);
+
+typedef void *GearToothObject;
+
+GearToothObject CreateGearTooth(UINT32 channel, bool directionSensitive = true);
+GearToothObject CreateGearTooth(UINT8 moduleNumber, UINT32 channel, bool directionSensitive = true);
+void StartGearTooth(GearToothObject o);
+void StopGearTooth(GearToothObject o);
+INT32 GetGearTooth(GearToothObject o);
+void ResetGearTooth(GearToothObject o);
+void DeleteGearTooth(GearToothObject o);
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CGyro.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CGyro.cpp
new file mode 100644
index 0000000..485624c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CGyro.cpp
@@ -0,0 +1,212 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "CInterfaces/CGyro.h"
+#include "Gyro.h"
+
+static Gyro* gyros[2] = {NULL, NULL};
+
+/**
+ * Allocate resoures for a Gyro.
+ *
+ * This is an internal routine and not used outside of this module.
+ *
+ * @param slot The analog module that the gyro is connected to. Must be slot 1 on the current
+ * hardware implementation.
+ * @param channel The analog channel the gyro is connected to. Must be channel 1 or 2 only (the only
+ * ones with the attached accumulator)
+ */
+static Gyro *AllocateGyro(UINT32 slot, UINT32 channel)
+{
+ Gyro *gyro = NULL;
+ if (slot == 1 && (channel == 1 || channel == 2))
+ {
+ if ((gyro = gyros[channel - 1]) == NULL)
+ {
+ gyro = new Gyro(channel);
+ gyros[channel - 1] = gyro;
+ }
+ }
+ return gyro;
+}
+
+/**
+ * Initialize the gyro.
+ * Calibrate the gyro by running for a number of samples and computing the center value for this
+ * part. Then use the center value as the Accumulator center value for subsequent measurements.
+ * It's important to make sure that the robot is not moving while the centering calculations are
+ * in progress, this is typically done when the robot is first turned on while it's sitting at
+ * rest before the competition starts.
+ *
+ * @param slot The slot the analog module is connected to
+ * @param channel The analog channel the gyro is plugged into
+ */
+void InitGyro(UINT32 slot, UINT32 channel)
+{
+ AllocateGyro(slot, channel);
+}
+
+/**
+ * Initialize the gyro.
+ * Calibrate the gyro by running for a number of samples and computing the center value for this
+ * part. Then use the center value as the Accumulator center value for subsequent measurements.
+ * It's important to make sure that the robot is not moving while the centering calculations are
+ * in progress, this is typically done when the robot is first turned on while it's sitting at
+ * rest before the competition starts.
+ *
+ * @param channel The analog channel the gyro is plugged into
+ */
+void InitGyro(UINT32 channel)
+{
+ InitGyro(SensorBase::GetDefaultAnalogModule(), channel);
+}
+
+/**
+ * Return the actual angle in degrees that the robot is currently facing.
+ *
+ * The angle is based on the current accumulator value corrected by the oversampling rate, the
+ * gyro type and the A/D calibration values.
+ * The angle is continuous, that is can go beyond 360 degrees. This make algorithms that wouldn't
+ * want to see a discontinuity in the gyro output as it sweeps past 0 on the second time around.
+ *
+ * @param slot The slot the analog module is connected to
+ * @param channel The analog channel the gyro is plugged into
+ * @return the current heading of the robot in degrees. This heading is based on integration
+ * of the returned rate from the gyro.
+ */
+float GetGyroAngle(UINT32 slot, UINT32 channel)
+{
+ Gyro *gyro = AllocateGyro(slot, channel);
+ if (gyro) return gyro->GetAngle();
+ return 0.0;
+}
+
+/**
+ * Return the actual angle in degrees that the robot is currently facing.
+ *
+ * The angle is based on the current accumulator value corrected by the oversampling rate, the
+ * gyro type and the A/D calibration values.
+ * The angle is continuous, that is can go beyond 360 degrees. This make algorithms that wouldn't
+ * want to see a discontinuity in the gyro output as it sweeps past 0 on the second time around.
+ *
+ * @param channel The analog channel the gyro is plugged into
+ * @return the current heading of the robot in degrees. This heading is based on integration
+ * of the returned rate from the gyro.
+ */
+float GetGyroAngle(UINT32 channel)
+{
+ return GetGyroAngle(SensorBase::GetDefaultAnalogModule(), channel);
+}
+
+/**
+ * Reset the gyro.
+ * Resets the gyro to a heading of zero. This can be used if there is significant
+ * drift in the gyro and it needs to be recalibrated after it has been running.
+
+ * @param slot The slot the analog module is connected to
+ * @param channel The analog channel the gyro is plugged into
+ */
+void ResetGyro(UINT32 slot, UINT32 channel)
+{
+ Gyro *gyro = AllocateGyro(slot, channel);
+ if (gyro) gyro->Reset();
+}
+
+/**
+ * Reset the gyro.
+ * Resets the gyro to a heading of zero. This can be used if there is significant
+ * drift in the gyro and it needs to be recalibrated after it has been running.
+
+ * @param channel The analog channel the gyro is plugged into
+ */
+void ResetGyro(UINT32 channel)
+{
+ ResetGyro(SensorBase::GetDefaultAnalogModule(), channel);
+}
+
+/**
+ * Set the gyro type based on the sensitivity.
+ * This takes the number of volts/degree/second sensitivity of the gyro and uses it in subsequent
+ * calculations to allow the code to work with multiple gyros.
+ *
+ * @param slot The slot the analog module is connected to
+ * @param channel The analog channel the gyro is plugged into
+ * @param voltsPerDegreePerSecond The type of gyro specified as the voltage that represents one degree/second.
+ */
+void SetGyroSensitivity(UINT32 slot, UINT32 channel, float voltsPerDegreePerSecond)
+{
+ Gyro *gyro = AllocateGyro(slot, channel);
+ if (gyro) gyro->SetSensitivity(voltsPerDegreePerSecond);
+}
+
+/**
+ * Set the gyro type based on the sensitivity.
+ * This takes the number of volts/degree/second sensitivity of the gyro and uses it in subsequent
+ * calculations to allow the code to work with multiple gyros.
+ *
+ * @param channel The analog channel the gyro is plugged into
+ * @param voltsPerDegreePerSecond The type of gyro specified as the voltage that represents one degree/second.
+ */
+void SetGyroSensitivity(UINT32 channel, float voltsPerDegreePerSecond)
+{
+ SetGyroSensitivity(SensorBase::GetDefaultAnalogModule(), channel, voltsPerDegreePerSecond);
+}
+
+/**
+ * Free the resources associated with this Gyro
+ * Free the Gyro object and the reservation for this slot/channel.
+ *
+ * @param slot The slot the analog module is connected to
+ * @param channel The analog channel the gyro is plugged into
+ */
+void DeleteGyro(UINT32 slot, UINT32 channel)
+{
+ if (slot == 1 && (channel == 1 || channel == 2))
+ {
+ delete gyros[channel - 1];
+ gyros[channel - 1] = NULL;
+ }
+}
+
+void DeleteGyro(UINT32 channel)
+{
+ DeleteGyro(SensorBase::GetDefaultAnalogModule(), channel);
+}
+
+/**
+ * Alternate C interface to Gyro
+ */
+
+GyroObject CreateGyro(UINT32 slot, UINT32 channel)
+{
+ return (GyroObject) new Gyro(slot, channel);
+}
+
+GyroObject CreateGyro(UINT32 channel)
+{
+ return (GyroObject) new Gyro(channel);
+}
+
+float GetGyroAngle(GyroObject o)
+{
+ return ((Gyro *) o)->GetAngle();
+}
+
+void ResetGyro(GyroObject o)
+{
+ ((Gyro *) o)->Reset();
+}
+
+void SetGyroSensitivity(GyroObject o, float voltsPerDegreePerSecond)
+{
+ ((Gyro *) o)->SetSensitivity(voltsPerDegreePerSecond);
+}
+
+void Delete(GyroObject o)
+{
+ delete ((Gyro *) o);
+}
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CGyro.h b/aos/externals/WPILib/WPILib/CInterfaces/CGyro.h
new file mode 100644
index 0000000..1c27533
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CGyro.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef C_GYRO_H
+#define C_GYRO_H
+
+#include <VxWorks.h>
+
+typedef void *GyroObject;
+
+GyroObject CreateGyro(UINT32 slot, UINT32 channel);
+GyroObject CreateGyro(UINT32 channel);
+float GetGyroAngle(GyroObject o);
+void ResetGyro(GyroObject o);
+void SetGyroSensitivity(GyroObject o, float voltsPerDegreePerSecond);
+void Delete(GyroObject o);
+
+void InitGyro(UINT32 slot, UINT32 channel);
+void InitGyro(UINT32 channel);
+float GetGyroAngle(UINT32 channel);
+float GetGyroAngle(UINT32 slot, UINT32 channel);
+void ResetGyro(UINT32 channel);
+void ResetGyro(UINT32 slot, UINT32 channel);
+void SetGyroSensitivity(UINT32 slot, UINT32 channel, float voltsPerDegreePerSecond);
+void SetGyroSensitivity(UINT32 channel, float voltsPerDegreePerSecond);
+void DeleteGyro(UINT32 slot, UINT32 channel);
+void DeleteGyro(UINT32 channel);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CJaguar.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CJaguar.cpp
new file mode 100644
index 0000000..88507e5
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CJaguar.cpp
@@ -0,0 +1,179 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Jaguar.h"
+#include "CInterfaces/CJaguar.h"
+#include "CInterfaces/CWrappers.h"
+#include "CInterfaces/CPWM.h"
+
+/**
+ * Create a Jaguar speed controller object.
+ * Allocate the object itself. This is a callback from the CPWM.cpp code to create the
+ * actual specific PWM object type.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel connected to this speed controller
+ */
+static SensorBase *CreateJaguarStatic(UINT32 slot, UINT32 channel)
+{
+ return new Jaguar(slot, channel);
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel connected to this speed controller
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ */
+void SetJaguarSpeed(UINT32 slot, UINT32 channel, float speed)
+{
+ Jaguar *jaguar = (Jaguar *) AllocatePWM(slot, channel, CreateJaguarStatic);
+ if (jaguar) jaguar->Set(speed);
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param channel The PWM channel connected to this speed controller
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ */
+void SetJaguarSpeed(UINT32 channel, float speed)
+{
+ Jaguar *jaguar = (Jaguar *) AllocatePWM(SensorBase::GetDefaultDigitalModule(), channel, CreateJaguarStatic);
+ if (jaguar) jaguar->Set(speed);
+}
+
+/**
+ * Set the PWM value directly to the hardware.
+ *
+ * Write a raw value to a PWM channel.
+ *
+ * @param channel The PWM channel connected to this speed controller
+ * @param value Raw PWM value. Range 0 - 255.
+ */
+void SetJaguarRaw(UINT32 channel, UINT8 value)
+{
+ Jaguar *jaguar = (Jaguar *) AllocatePWM(SensorBase::GetDefaultDigitalModule(), channel, CreateJaguarStatic);
+ if (jaguar) jaguar->SetRaw(value);
+}
+
+/**
+ * Get the PWM value directly from the hardware.
+ *
+ * Read a raw value from a PWM channel.
+ *
+ * @param channel The PWM channel connected to this speed controller
+ * @return Raw PWM control value. Range: 0 - 255.
+ */
+UINT8 GetJaguarRaw(UINT32 channel)
+{
+ Jaguar *jaguar = (Jaguar *) AllocatePWM(SensorBase::GetDefaultDigitalModule(), channel, CreateJaguarStatic);
+ if (jaguar)
+ return jaguar->GetRaw();
+ else
+ return 0;
+}
+
+/**
+ * Set the PWM value directly to the hardware.
+ *
+ * Write a raw value to a PWM channel.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel connected to this speed controller
+ * @param value Raw PWM value. Range 0 - 255.
+ */
+void SetJaguarRaw(UINT32 slot, UINT32 channel, UINT8 value)
+{
+ Jaguar *jaguar = (Jaguar *) AllocatePWM(slot, channel, CreateJaguarStatic);
+ if (jaguar) jaguar->SetRaw(value);
+}
+
+/**
+ * Get the PWM value directly from the hardware.
+ *
+ * Read a raw value from a PWM channel.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel connected to this speed controller
+ * @return Raw PWM control value. Range: 0 - 255.
+ */
+UINT8 GetJaguarRaw(UINT32 slot, UINT32 channel)
+{
+ Jaguar *jaguar = (Jaguar *) AllocatePWM(slot, channel, CreateJaguarStatic);
+ if (jaguar)
+ return jaguar->GetRaw();
+ else
+ return 0;
+}
+
+/**
+ * Free the underlying Jaguar object.
+ * Free the underlying object and free the associated resources.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel connected to this speed controller
+ */
+void DeleteJaguar(UINT32 slot, UINT32 channel)
+{
+ Jaguar *jaguar = (Jaguar *) AllocatePWM(slot, channel, CreateJaguarStatic);
+ DeletePWM(slot, channel);
+ delete jaguar;
+}
+
+/**
+ * Free the underlying Jaguar object.
+ * Free the underlying object and free the associated resources.
+ *
+ * @param channel The PWM channel connected to this speed controller
+ */
+void DeleteJaguar(UINT32 channel)
+{
+ DeleteJaguar(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+
+/*
+ * Alternate interface to Jaguar
+ */
+
+JaguarObject CreateJaguar(UINT32 module, UINT32 channel)
+{
+ return (JaguarObject) new Jaguar(module, channel);
+}
+
+JaguarObject CreateJaguar(UINT32 channel)
+{
+ return (JaguarObject) new Jaguar(channel);
+}
+
+void SetJaguarRaw(JaguarObject o, UINT8 value)
+{
+ ((Jaguar *) o)->SetRaw(value);
+}
+
+void SetJaguarSpeed(JaguarObject o, float speed)
+{
+ ((Jaguar *) o)->Set(speed);
+}
+
+UINT8 GetJaguarRaw(JaguarObject o)
+{
+ return ((Jaguar *)o)->GetRaw();
+}
+
+void DeleteJaguar(JaguarObject o)
+{
+ delete (Jaguar *) o;
+}
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CJaguar.h b/aos/externals/WPILib/WPILib/CInterfaces/CJaguar.h
new file mode 100644
index 0000000..eca456c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CJaguar.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef C_JAGUAR_H
+#define C_JAGUAR_H
+
+void SetJaguarSpeed(UINT32 module, UINT32 channel, float speed);
+void SetJaguarSpeed(UINT32 channel, float speed);
+void SetJaguarRaw(UINT32 channel, UINT8 value);
+UINT8 GetJaguarRaw(UINT32 channel);
+void SetJaguarRaw(UINT32 module, UINT32 channel, UINT8 value);
+UINT8 GetJaguarRaw(UINT32 module, UINT32 channel);
+void DeleteJaguar(UINT32 module, UINT32 channel);
+void DeleteJaguar(UINT32 channel);
+
+typedef void *JaguarObject;
+
+JaguarObject CreateJaguar(UINT32 module, UINT32 channel);
+JaguarObject CreateJaguar(UINT32 channel);
+void SetJaguarRaw(JaguarObject o, UINT8 value);
+void SetJaguarSpeed(JaguarObject o, float speed);
+UINT8 GetJaguarRaw(JaguarObject o);
+void DeleteJaguar(JaguarObject o);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CJoystick.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CJoystick.cpp
new file mode 100644
index 0000000..b388640
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CJoystick.cpp
@@ -0,0 +1,237 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Joystick.h"
+#include "CInterfaces/CJoystick.h"
+
+static Joystick *joysticks[4];
+static bool initialized = false;
+
+/**
+ * Get the joystick associated with a port.
+ * An internal function that will return the joystick object associated with a given
+ * joystick port number. On the first call, all four joysticks are preallocated.
+ *
+ * @param port The joystick (USB) port number
+ */
+static Joystick *getJoystick(UINT32 port)
+{
+ if (!initialized)
+ {
+ for (int i = 0; i < 4; i++)
+ {
+ joysticks[i] = new Joystick(i+1);
+ }
+ initialized = true;
+ }
+ if (port < 1 || port > 4) return NULL;
+ return joysticks[port - 1];
+}
+
+
+/**
+ * Get the channel currently associated with the specified axis.
+ *
+ * @param port The USB port for this joystick.
+ * @param axis The axis to look up the channel for.
+ * @return The channel fr the axis.
+ */
+UINT32 GetAxisChannel(UINT32 port, AxisType axis)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetAxisChannel((Joystick::AxisType) axis);
+}
+
+/**
+ * Set the channel associated with a specified axis.
+ *
+ * @param port The USB port for this joystick.
+ * @param axis The axis to set the channel for.
+ * @param channel The channel to set the axis to.
+ */
+void SetAxisChannel(UINT32 port, AxisType axis, UINT32 channel)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return;
+ stick->SetAxisChannel((Joystick::AxisType) axis, channel);
+}
+
+/**
+ * Get the X value of the joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ *
+ * @param port The USB port for this joystick.
+ */
+float GetX(UINT32 port, JoystickHand hand)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetX((Joystick::JoystickHand) hand);
+}
+
+/**
+ * Get the Y value of the joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ *
+ * @param port The USB port for this joystick.
+ */
+float GetY(UINT32 port, JoystickHand hand)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetY((Joystick::JoystickHand) hand);
+}
+
+/**
+ * Get the Z value of the current joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ *
+ * @param port The USB port for this joystick.
+ */
+float GetZ(UINT32 port)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetZ();
+}
+
+/**
+ * Get the twist value of the current joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ *
+ * @param port The USB port for this joystick.
+ */
+float GetTwist(UINT32 port)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetTwist();
+}
+
+/**
+ * Get the throttle value of the current joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ *
+ * @param port The USB port for this joystick.
+ */
+float GetThrottle(UINT32 port)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetThrottle();
+}
+
+/**
+ * For the current joystick, return the axis determined by the argument.
+ *
+ * This is for cases where the joystick axis is returned programatically, otherwise one of the
+ * previous functions would be preferable (for example GetX()).
+ *
+ * @param port The USB port for this joystick.
+ * @param axis The axis to read.
+ * @return The value of the axis.
+ */
+float GetAxis(UINT32 port, AxisType axis)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetAxis((Joystick::AxisType) axis);
+}
+
+/**
+ * Get the value of the axis.
+ *
+ * @param port The USB port for this joystick.
+ * @param axis The axis to read [1-6].
+ * @return The value of the axis.
+ */
+float GetRawAxis(UINT32 port, UINT32 axis)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetRawAxis(axis);
+}
+
+/**
+ * Read the state of the trigger on the joystick.
+ *
+ * Look up which button has been assigned to the trigger and read its state.
+ *
+ * @param port The USB port for this joystick.
+ * @param hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface.
+ * @return The state of the trigger.
+ */
+bool GetTrigger(UINT32 port, JoystickHand hand)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetTrigger((Joystick::JoystickHand) hand);
+}
+
+/**
+ * Read the state of the top button on the joystick.
+ *
+ * Look up which button has been assigned to the top and read its state.
+ *
+ * @param port The USB port for this joystick.
+ * @param hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface.
+ * @return The state of the top button.
+ */
+bool GetTop(UINT32 port, JoystickHand hand)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetTop((Joystick::JoystickHand) hand);
+}
+
+/**
+ * This is not supported for the Joystick.
+ * This method is only here to complete the GenericHID interface.
+ *
+ * @param port The USB port for this joystick.
+ */
+bool GetBumper(UINT32 port, JoystickHand hand)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetBumper((Joystick::JoystickHand) hand);
+}
+
+/**
+ * Get buttons based on an enumerated type.
+ *
+ * The button type will be looked up in the list of buttons and then read.
+ *
+ * @param port The USB port for this joystick.
+ * @param button The type of button to read.
+ * @return The state of the button.
+ */
+bool GetButton(UINT32 port, ButtonType button)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetButton((Joystick::ButtonType) button);
+}
+
+/**
+ * Get the button value for buttons 1 through 12.
+ *
+ * The buttons are returned in a single 16 bit value with one bit representing the state
+ * of each button. The appropriate button is returned as a boolean value.
+ *
+ * @param port The USB port for this joystick.
+ * @param button The button number to be read.
+ * @return The state of the button.
+ **/
+bool GetRawButton(UINT32 port, UINT32 button)
+{
+ Joystick *stick = getJoystick(port);
+ if (stick == NULL) return 0;
+ return stick->GetRawButton(button);
+}
+
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CJoystick.h b/aos/externals/WPILib/WPILib/CInterfaces/CJoystick.h
new file mode 100644
index 0000000..7e278bd
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CJoystick.h
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef _C_JOYSTICK_H_
+#define _C_JOYSTICK_H_
+
+static const UINT32 kDefaultXAxis = 1;
+static const UINT32 kDefaultYAxis = 2;
+static const UINT32 kDefaultZAxis = 3;
+static const UINT32 kDefaultTwistAxis = 4;
+static const UINT32 kDefaultThrottleAxis = 3;
+
+typedef enum {
+ kLeftHand = 0,
+ kRightHand = 1
+} JoystickHand;
+
+typedef enum
+{
+ kXAxis, kYAxis, kZAxis, kTwistAxis, kThrottleAxis, kNumAxisTypes
+} AxisType;
+static const UINT32 kDefaultTriggerButton = 1;
+static const UINT32 kDefaultTopButton = 2;
+typedef enum
+{
+ kTriggerButton, kTopButton, kNumButtonTypes
+} ButtonType;
+
+UINT32 GetAxisChannel(UINT32 port, AxisType axis);
+void SetAxisChannel(UINT32 port, AxisType axis, UINT32 channel);
+
+float GetX(UINT32 port, JoystickHand hand = kRightHand);
+float GetY(UINT32 port, JoystickHand hand = kRightHand);
+float GetZ(UINT32 port);
+float GetTwist(UINT32 port);
+float GetThrottle(UINT32 port);
+float GetAxis(UINT32 port, AxisType axis);
+float GetRawAxis(UINT32 port, UINT32 axis);
+
+bool GetTrigger(UINT32 port, JoystickHand hand = kRightHand);
+bool GetTop(UINT32 port, JoystickHand hand = kRightHand);
+bool GetBumper(UINT32 port, JoystickHand hand = kRightHand);
+bool GetButton(UINT32 port, ButtonType button);
+bool GetRawButton(UINT32 port, UINT32 button);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CPWM.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CPWM.cpp
new file mode 100644
index 0000000..50e7e76
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CPWM.cpp
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "CInterfaces/CPWM.h"
+#include "PWM.h"
+#include "CInterfaces/CWrappers.h"
+#include "DigitalModule.h"
+
+static bool PWMsInitialized = false;
+static PWM *PWMs[SensorBase::kDigitalModules][SensorBase::kPwmChannels];
+
+/**
+ * Alloate a PWM based object
+ *
+ * Allocate an instance of a PWM based object. This code is shared between the subclasses
+ * of PWM and is not usually created as a standalone object.
+ *
+ * @param module The slot the digital module is plugged into that corresponds to this serial port
+ * @param channel The PWM channel for this PWM object
+ * @param createObject The function callback in the subclass object that actually creates an instance
+ * of the appropriate class.
+ */
+PWM *AllocatePWM(UINT8 moduleNumber, UINT32 channel, SensorCreator createObject)
+{
+ if (!PWMsInitialized)
+ {
+ for (unsigned i = 0; i < SensorBase::kDigitalModules; i++)
+ for (unsigned j = 0; j < SensorBase::kPwmChannels; j++)
+ PWMs[i][j] = NULL;
+ PWMsInitialized = true;
+ }
+ if (!SensorBase::CheckPWMModule(moduleNumber) || !SensorBase::CheckPWMChannel(channel))
+ return NULL;
+ PWM *pwm = PWMs[moduleNumber - 1][channel - 1];
+ if (pwm == NULL)
+ {
+ pwm = (PWM *) createObject(moduleNumber, channel);
+ PWMs[moduleNumber - 1][channel - 1] = pwm;
+ }
+ return pwm;
+}
+
+/**
+ * Alloate a PWM based object
+ *
+ * Allocate an instance of a PWM based object. This code is shared between the subclasses
+ * of PWM and is not usually created as a standalone object.
+ *
+ * @param channel The PWM channel for this PWM object
+ * @param createObject The function callback in the subclass object that actually creates an instance
+ * of the appropriate class.
+ */
+PWM *AllocatePWM(UINT32 channel, SensorCreator createObject)
+{
+ return AllocatePWM(SensorBase::GetDefaultDigitalModule(), channel, createObject);
+}
+
+/**
+ * Delete a PWM
+ * Delete a PWM and free up all the associated resources for this object.
+ *
+ * @param slot The slot the digital module is plugged into that corresponds to this serial port
+ * @param channel The PWM channel for this PWM object
+ */
+void DeletePWM(UINT8 moduleNumber, UINT32 channel)
+{
+ if (SensorBase::CheckPWMModule(moduleNumber) && SensorBase::CheckPWMChannel(channel))
+ {
+ PWMs[moduleNumber - 1][channel - 1] = NULL;
+ }
+}
+
+/**
+ * Delete a PWM
+ * Delete a PWM and free up all the associated resources for this object.
+ *
+ * @param channel The PWM channel for this PWM object
+ */
+void DeletePWM(UINT32 channel)
+{
+ DeletePWM(SensorBase::GetDefaultDigitalModule(), channel);
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CPWM.h b/aos/externals/WPILib/WPILib/CInterfaces/CPWM.h
new file mode 100644
index 0000000..b9fb646
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CPWM.h
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef C_PWM_H
+#define C_PWM_H
+
+#include <VxWorks.h>
+#include "CWrappers.h"
+#include "PWM.h"
+
+PWM *AllocatePWM(UINT8 moduleNumber, UINT32 channel, SensorCreator creator);
+PWM *AllocatePWM(UINT32 channel, SensorCreator creator);
+void DeletePWM(UINT8 moduleNumber, UINT32 channel);
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CRelay.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CRelay.cpp
new file mode 100644
index 0000000..07e1d01
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CRelay.cpp
@@ -0,0 +1,202 @@
+#include "SensorBase.h"
+#include "DigitalModule.h"
+#include "Relay.h"
+#include "CInterfaces/CRelay.h"
+
+static Relay* relays[SensorBase::kDigitalModules][SensorBase::kRelayChannels];
+static bool initialized = false;
+static Relay::Direction s_direction = Relay::kBothDirections;
+
+/**
+ * Internal function to allocate Relay objects.
+ * This function handles the mapping between channel/slot numbers to relay objects. It also
+ * allocates Relay objects if they are not already allocated.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The relay channel for this device
+ */
+static Relay *AllocateRelay(UINT8 moduleNumber, UINT32 channel)
+{
+ if (!initialized)
+ {
+ for (unsigned i = 0; i < SensorBase::kDigitalModules; i++)
+ for (unsigned j = 0; j < SensorBase::kRelayChannels; j++)
+ relays[i][j] = NULL;
+ initialized = true;
+ }
+ if (SensorBase::CheckRelayModule(moduleNumber) && SensorBase::CheckRelayChannel(channel))
+ {
+ unsigned slotOffset = moduleNumber - 1;
+ if (relays[slotOffset][channel - 1] == NULL)
+ {
+ relays[slotOffset][channel - 1] = new Relay(moduleNumber, channel, s_direction);
+ }
+ return relays[slotOffset][channel - 1];
+ }
+ return NULL;
+}
+
+/**
+ * Set the direction that this relay object will control.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The relay channel number for this object
+ * @param direction The direction that the relay object will control
+ */
+void InitRelay(UINT8 moduleNumber, UINT32 channel, RelayDirection direction)
+{
+ switch (direction)
+ {
+ case kBothDirections:
+ s_direction = Relay::kBothDirections;
+ break;
+ case kForwardOnly:
+ s_direction = Relay::kForwardOnly;
+ break;
+ case kReverseOnly:
+ s_direction = Relay::kReverseOnly;
+ break;
+ default:
+ s_direction = Relay::kBothDirections;
+ }
+ AllocateRelay(moduleNumber, channel);
+}
+
+/**
+ * Set the direction that this relay object will control.
+ *
+ * @param channel The relay channel number for this object
+ * @param direction The direction that the relay object will control
+ */
+void InitRelay(UINT32 channel, RelayDirection direction)
+{
+ InitRelay(SensorBase::GetDefaultDigitalModule(), channel, direction);
+}
+
+/**
+ * Free up the resources associated with this relay.
+ * Delete the underlying Relay object and make the channel/port available for reuse.
+ *
+ * @param slot The slot that the digital module is plugged into
+ * @param channel The relay channel number for this object
+ */
+void DeleteRelay(UINT8 moduleNumber, UINT32 channel)
+{
+ if (SensorBase::CheckRelayModule(moduleNumber) && SensorBase::CheckRelayChannel(channel))
+ {
+ unsigned slotOffset = moduleNumber - 1;
+ delete relays[slotOffset][channel - 1];
+ relays[slotOffset][channel - 1] = NULL;
+ }
+}
+
+/**
+ * Free up the resources associated with this relay.
+ * Delete the underlying Relay object and make the channel/port available for reuse.
+ *
+ * @param channel The relay channel number for this object
+ */
+void DeleteRelay(UINT32 channel)
+{
+ DeleteRelay(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+/**
+ * Set the relay state.
+ *
+ * Valid values depend on which directions of the relay are controlled by the object.
+ *
+ * When set to kBothDirections, the relay can only be one of the three reasonable
+ * values, 0v-0v, 0v-12v, or 12v-0v.
+ *
+ * When set to kForwardOnly or kReverseOnly, you can specify the constant for the
+ * direction or you can simply specify kOff and kOn. Using only kOff and kOn is
+ * recommended.
+ *
+ * @param slot The slot that the digital module is plugged into
+ * @param channel The relay channel number for this object
+ * @param value The state to set the relay.
+ */
+void SetRelay(UINT8 moduleNumber, UINT32 channel, RelayValue value)
+{
+ Relay *relay = AllocateRelay(moduleNumber, channel);
+ if (relay != NULL)
+ {
+ switch (value)
+ {
+ case kOff: relay->Set(Relay::kOff); break;
+ case kOn: relay->Set(Relay::kOn); break;
+ case kForward: relay->Set(Relay::kForward); break;
+ case kReverse: relay->Set(Relay::kReverse); break;
+ }
+ }
+}
+
+/**
+ * Set the relay state.
+ *
+ * Valid values depend on which directions of the relay are controlled by the object.
+ *
+ * When set to kBothDirections, the relay can only be one of the three reasonable
+ * values, 0v-0v, 0v-12v, or 12v-0v.
+ *
+ * When set to kForwardOnly or kReverseOnly, you can specify the constant for the
+ * direction or you can simply specify kOff and kOn. Using only kOff and kOn is
+ * recommended.
+ *
+ * @param channel The relay channel number for this object
+ * @param value The state to set the relay.
+ */
+void SetRelay(UINT32 channel, RelayValue value)
+{
+ SetRelay(SensorBase::GetDefaultDigitalModule(), channel, value);
+}
+
+
+/**
+ * Alternate C Interface
+ */
+
+RelayObject CreateRelay(UINT8 moduleNumber, UINT32 channel, RelayDirection direction)
+{
+ switch (direction)
+ {
+ case kForwardOnly:
+ return new Relay(moduleNumber, channel, Relay::kForwardOnly);
+ case kReverseOnly:
+ return new Relay(moduleNumber, channel, Relay::kReverseOnly);
+ case kBothDirections:
+ default:
+ return new Relay(moduleNumber, channel, Relay::kBothDirections);
+ }
+}
+
+RelayObject CreateRelay(UINT32 channel, RelayDirection direction)
+{
+ switch (direction)
+ {
+ case kForwardOnly:
+ return new Relay(channel, Relay::kForwardOnly);
+ case kReverseOnly:
+ return new Relay(channel, Relay::kReverseOnly);
+ case kBothDirections:
+ default:
+ return new Relay(channel, Relay::kBothDirections);
+ }
+}
+
+void SetRelay(RelayObject o, RelayValue value)
+{
+ switch (value)
+ {
+ case kOff: ((Relay *)o )->Set(Relay::kOff); break;
+ case kOn: ((Relay *)o )->Set(Relay::kOn); break;
+ case kForward: ((Relay *)o )->Set(Relay::kForward); break;
+ case kReverse: ((Relay *)o )->Set(Relay::kReverse); break;
+ }
+}
+
+void DeleteRelay(RelayObject o)
+{
+ delete (Relay *) o;
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CRelay.h b/aos/externals/WPILib/WPILib/CInterfaces/CRelay.h
new file mode 100644
index 0000000..140018d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CRelay.h
@@ -0,0 +1,24 @@
+#ifndef _C_RELAY_H
+#define _C_RELAY_H
+
+typedef enum {kOff, kOn, kForward, kReverse} RelayValue;
+typedef enum {kBothDirections, kForwardOnly, kReverseOnly} RelayDirection;
+
+void InitRelay(UINT32 channel, RelayDirection direction = kBothDirections);
+void InitRelayRelay(UINT8 moduleNumber, UINT32 channel, RelayDirection direction = kBothDirections);
+
+void DeleteRelay(UINT32 channel);
+void DeleteRelay(UINT8 moduleNumber, UINT32 channel);
+
+void SetRelay(UINT32 channel, RelayValue value);
+void SetRelay(UINT8 moduleNumber, UINT32 channel, RelayValue value);
+
+typedef void *RelayObject;
+
+RelayObject CreateRelay(UINT8 moduleNumber, UINT32 channel, RelayDirection direction = kBothDirections);
+RelayObject CreateRelay(UINT32 channel, RelayDirection direction = kBothDirections);
+void SetRelay(RelayObject o, RelayValue value);
+void DeleteRelay(RelayObject o);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CRobotDrive.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CRobotDrive.cpp
new file mode 100644
index 0000000..48faf78
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CRobotDrive.cpp
@@ -0,0 +1,153 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "CInterfaces/CRobotDrive.h"
+#include "Joystick.h"
+#include "RobotDrive.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+static RobotDrive *drive = NULL;
+
+/*
+ * Driving functions
+ * These functions provide an interface to multiple motors that is used for C programming
+ * The Drive(speed, direction) function is the main part of the set that makes it easy
+ * to set speeds and direction independently in one call.
+ */
+
+/**
+ * Create a RobotDrive with 4 motors specified with channel numbers.
+ * Set up parameters for a four wheel drive system where all four motor
+ * pwm channels are specified in the call.
+ * This call assumes Jaguars for controlling the motors.
+ *
+ * @param frontLeftMotor Front left motor channel number on the default digital module
+ * @param rearLeftMotor Rear Left motor channel number on the default digital module
+ * @param frontRightMotor Front right motor channel number on the default digital module
+ * @param rearRightMotor Rear Right motor channel number on the default digital module
+ */
+void CreateRobotDrive(UINT32 frontLeftMotor, UINT32 rearLeftMotor,
+ UINT32 frontRightMotor, UINT32 rearRightMotor)
+{
+ if (drive == NULL)
+ drive = new RobotDrive(frontLeftMotor, rearLeftMotor,
+ frontRightMotor, rearRightMotor);
+}
+
+/**
+ * Constructor for RobotDrive with 2 motors specified with channel numbers.
+ * Set up parameters for a four wheel drive system where all four motor
+ * pwm channels are specified in the call.
+ * This call assumes Jaguars for controlling the motors.
+ *
+ * @param leftMotor Front left motor channel number on the default digital module
+ * @param rightMotor Front right motor channel number on the default digital module
+ */
+void CreateRobotDrive(UINT32 leftMotor, UINT32 rightMotor)
+{
+ if (drive == NULL)
+ drive = new RobotDrive(leftMotor, rightMotor);
+}
+
+/**
+ * Drive the motors at "speed" and "curve".
+ *
+ * The speed and curve are -1.0 to +1.0 values where 0.0 represents stopped and
+ * not turning. The algorithm for adding in the direction attempts to provide a constant
+ * turn radius for differing speeds.
+ *
+ * This function sill most likely be used in an autonomous routine.
+ *
+ * @param speed The forward component of the speed to send to the motors.
+ * @param curve The rate of turn, constant for different forward speeds.
+ */
+void Drive(float speed, float curve)
+{
+ if (drive == NULL)
+ wpi_setGlobalWPIError(DriveUninitialized);
+ else
+ drive->Drive(speed, curve);
+}
+
+/**
+ * Provide tank steering using the stored robot configuration.
+ * Drive the robot using two joystick inputs. The Y-axis will be selected from
+ * each Joystick object.
+ *
+ * @param leftStickPort The joystick port to control the left side of the robot.
+ * @param rightStickPort The joystick port to control the right side of the robot.
+ */
+void TankDrive(UINT32 leftStickPort, UINT32 rightStickPort)
+{
+ if (drive == NULL)
+ {
+ wpi_setGlobalWPIError(DriveUninitialized);
+ }
+ else
+ {
+ Joystick *leftStick = Joystick::GetStickForPort(leftStickPort);
+ Joystick *rightStick = Joystick::GetStickForPort(rightStickPort);
+ drive->TankDrive(leftStick, rightStick);
+ }
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * Given a single Joystick, the class assumes the Y axis for the move value and the X axis
+ * for the rotate value.
+ * (Should add more information here regarding the way that arcade drive works.)
+ *
+ * @param stickPort The joystick to use for Arcade single-stick driving. The Y-axis will be selected
+ * for forwards/backwards and the X-axis will be selected for rotation rate.
+ * @param squaredInputs If true, the sensitivity will be increased for small values
+ */
+void ArcadeDrive(UINT32 stickPort, bool squaredInputs)
+{
+ if (drive == NULL)
+ {
+ wpi_setGlobalWPIError(DriveUninitialized);
+ }
+ else
+ {
+ Joystick *stick = Joystick::GetStickForPort(stickPort);
+ drive->ArcadeDrive(stick);
+ }
+}
+
+/**
+ * Provide tank steering using the stored robot configuration.
+ * This function lets you directly provide joystick values from any source.
+ * @param leftSpeed The value of the left stick.
+ * @param rightSpeed The value of the right stick.
+ */
+void TankByValue(float leftSpeed, float rightSpeed)
+{
+ if (drive == NULL)
+ {
+ wpi_setGlobalWPIError(DriveUninitialized);
+ }
+ else
+ {
+ drive->Drive(leftSpeed, rightSpeed);
+ }
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * This function lets you directly provide joystick values from any source.
+ *
+ * @param moveValue The value to use for fowards/backwards
+ * @param rotateValue The value to use for the rotate right/left
+ * @param squaredInputs If set, increases the sensitivity at low speeds
+ */
+void ArcadeByValue(float moveValue, float rotateValue, bool squaredInputs)
+{
+ if (drive == NULL)
+ wpi_setGlobalWPIError(DriveUninitialized);
+ else
+ drive->ArcadeDrive(moveValue, rotateValue, squaredInputs);
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CRobotDrive.h b/aos/externals/WPILib/WPILib/CInterfaces/CRobotDrive.h
new file mode 100644
index 0000000..f547ff7
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CRobotDrive.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef C_ROBOT_DRIVE_H
+#define C_ROBOT_DRIVE_H
+
+#include <VxWorks.h>
+
+void CreateRobotDrive(UINT32 leftMotor, UINT32 rightMotor);
+void CreateRobotDrive(UINT32 frontLeftMotor, UINT32 rearLeftMotor,
+ UINT32 frontRightMotor, UINT32 rearRightMotor);
+void Drive(float speed, float curve);
+void TankDrive(UINT32 leftStickPort, UINT32 rightStickPort);
+void ArcadeDrive(UINT32 stickPort, bool squaredInputs = false);
+void TankByValue(float leftSpeed, float rightSpeed);
+void ArcadeByValue(float moveSpeed, float rotateSpeed, bool squaredInputs = false);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CSerialPort.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CSerialPort.cpp
new file mode 100644
index 0000000..9d00f30
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CSerialPort.cpp
@@ -0,0 +1,174 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#include "CInterfaces/CSerialPort.h"
+#include <visa/visa.h>
+
+static SerialPort* serial_port = NULL;
+
+/**
+ * Open the serial port object.
+ * Open and allocate the serial port.
+ *
+ * @param baudRate The baud rate to configure the serial port. The cRIO-9074 supports up to 230400 Baud.
+ * @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
+ * @param parity Select the type of parity checking to use.
+ * @param stopBits The number of stop bits to use as defined by the enum StopBits.
+ */
+void OpenSerialPort(UINT32 baudRate, UINT8 dataBits, SerialPort::Parity parity, SerialPort::StopBits stopBits)
+{
+ if (serial_port == NULL)
+ {
+ serial_port = new SerialPort(baudRate, dataBits, parity, stopBits);
+ }
+}
+
+/**
+ * Set the type of flow control to enable on this port.
+ *
+ * By default, flow control is disabled.
+ */
+void SetSerialFlowControl(SerialPort::FlowControl flowControl)
+{
+ serial_port->SetFlowControl(flowControl);
+}
+
+/**
+ * Enable termination and specify the termination character.
+ *
+ * Termination is currently only implemented for receive.
+ * When the the terminator is recieved, the Read() or Scanf() will return
+ * fewer bytes than requested, stopping after the terminator.
+ *
+ * @param terminator The character to use for termination.
+ */
+void EnableSerialTermination(char terminator)
+{
+ serial_port->EnableTermination(terminator);
+}
+
+/**
+ * Disable termination behavior.
+ */
+void DisableSerialTermination()
+{
+ serial_port->DisableTermination();
+}
+
+/**
+ * Get the number of bytes currently available to read from the serial port.
+ *
+ * @return The number of bytes available to read.
+ */
+INT32 GetSerialBytesReceived()
+{
+ return serial_port->GetBytesReceived();
+}
+
+/**
+ * Output formatted text to the serial port.
+ *
+ * @bug All pointer-based parameters seem to return an error.
+ *
+ * @param writeFmt A string that defines the format of the output.
+ */
+void PrintfSerial(const char *writeFmt, ...)
+{
+ va_list args;
+
+ va_start (args, writeFmt);
+ serial_port->Printf((ViString)writeFmt, args);
+ va_end (args);
+}
+
+/**
+ * Input formatted text from the serial port.
+ *
+ * @bug All pointer-based parameters seem to return an error.
+ *
+ * @param readFmt A string that defines the format of the input.
+ */
+void ScanfSerial(const char *readFmt, ...)
+{
+ va_list args;
+
+ va_start (args, readFmt);
+ serial_port->Scanf((ViString)readFmt, args);
+ va_end (args);
+}
+
+/**
+ * Read raw bytes out of the buffer.
+ *
+ * @param buffer Pointer to the buffer to store the bytes in.
+ * @param count The maximum number of bytes to read.
+ * @return The number of bytes actually read into the buffer.
+ */
+UINT32 ReadSerialPort(char *buffer, INT32 count)
+{
+ return serial_port->Read(buffer, count);
+}
+
+/**
+ * Write raw bytes to the buffer.
+ *
+ * @param buffer Pointer to the buffer to read the bytes from.
+ * @param count The maximum number of bytes to write.
+ * @return The number of bytes actually written into the port.
+ */
+UINT32 WriteSerialPort(const char *buffer, INT32 count)
+{
+ return serial_port->Write(buffer, count);
+}
+
+/**
+ * Configure the timeout of the serial port.
+ *
+ * This defines the timeout for transactions with the hardware.
+ * It will affect reads and very large writes.
+ *
+ * @param timeout The number of seconds to to wait for I/O.
+ */
+void SetSerialTimeout(INT32 timeout)
+{
+ serial_port->SetTimeout(timeout);
+}
+
+/**
+ * Specify the flushing behavior of the output buffer.
+ *
+ * When set to kFlushOnAccess, data is synchronously written to the serial port
+ * after each call to either Printf() or Write().
+ *
+ * When set to kFlushWhenFull, data will only be written to the serial port when
+ * the buffer is full or when Flush() is called.
+ *
+ * @param mode The write buffer mode.
+ */
+void SetSerialWriteBufferMode(SerialPort::WriteBufferMode mode)
+{
+ serial_port->SetWriteBufferMode(mode);
+}
+
+/**
+ * Force the output buffer to be written to the port.
+ *
+ * This is used when SetWriteBufferMode() is set to kFlushWhenFull to force a
+ * flush before the buffer is full.
+ */
+void FlushSerialPort()
+{
+ serial_port->Flush();
+}
+
+/**
+ * Reset the serial port driver to a known state.
+ *
+ * Empty the transmit and receive buffers in the device and formatted I/O.
+ */
+void ResetSerialPort()
+{
+ serial_port->Reset();
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CSerialPort.h b/aos/externals/WPILib/WPILib/CInterfaces/CSerialPort.h
new file mode 100644
index 0000000..91f7c3e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CSerialPort.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#ifndef _SERIALPORT_H
+#define _SERIALPORT_H
+
+#include "SerialPort.h"
+
+void OpenSerialPort(UINT32 baudRate, UINT8 dataBits, SerialPort::Parity parity, SerialPort::StopBits stopBits);
+void SetSerialFlowControl(SerialPort::FlowControl flowControl);
+void EnableSerialTermination(char terminator);
+void DisableSerialTermination();
+INT32 GetSerialBytesReceived();
+void PrintfSerial(const char *writeFmt, ...);
+void ScanfSerial(const char *readFmt, ...);
+UINT32 ReadSerialPort(char *buffer, INT32 count);
+UINT32 WriteSerialPort(const char *buffer, INT32 count);
+void SetSerialTimeout(INT32 timeout_ms);
+void SetSerialWriteBufferMode(SerialPort::WriteBufferMode mode);
+void FlushSerialPort();
+void ResetSerialPort();
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CServo.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CServo.cpp
new file mode 100644
index 0000000..50b585e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CServo.cpp
@@ -0,0 +1,256 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Servo.h"
+#include "CInterfaces/CServo.h"
+#include "CInterfaces/CPWM.h"
+
+static SensorBase *CreateServoStatic(UINT32 slot, UINT32 channel)
+{
+ return new Servo(slot, channel);
+}
+
+/**
+ * Set the servo position.
+ *
+ * Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel in the module the servo is plugged into
+ * @param value Position from 0.0 to 1.0.
+ */
+void SetServo(UINT32 slot, UINT32 channel, float value)
+{
+ Servo *servo = (Servo *) AllocatePWM(slot, channel, CreateServoStatic);
+ servo->Set(value);
+}
+
+/**
+ * Get the servo position.
+ *
+ * Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel in the module the servo is plugged into
+ * @return Position from 0.0 to 1.0.
+ */
+float GetGetServo(UINT32 slot, UINT32 channel)
+{
+ Servo *servo = (Servo *) AllocatePWM(slot, channel, CreateServoStatic);
+ return servo->Get();
+}
+
+/**
+ * Set the servo angle.
+ *
+ * Assume that the servo angle is linear with respect to the PWM value (big assumption, need to test).
+ *
+ * Servo angles that are out of the supported range of the servo simply "saturate" in that direction
+ * In other words, if the servo has a range of (X degrees to Y degrees) than angles of less than X
+ * result in an angle of X being set and angles of more than Y degrees result in an angle of Y being set.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel in the module the servo is plugged into
+ * @param angle The angle in degrees to set the servo.
+ */
+void SetServoAngle(UINT32 slot, UINT32 channel, float angle)
+{
+ Servo *servo = (Servo *) AllocatePWM(slot, channel, CreateServoStatic);
+ servo->SetAngle(angle);
+}
+
+/**
+ * Get the servo angle.
+ *
+ * Assume that the servo angle is linear with respect to the PWM value (big assumption, need to test).
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel in the module the servo is plugged into
+ * @return The angle in degrees to which the servo is set.
+ */
+float GetServoAngle(UINT32 slot, UINT32 channel)
+{
+ Servo *servo = (Servo *) AllocatePWM(slot, channel, CreateServoStatic);
+ return servo->GetAngle();
+}
+
+/**
+ * Get the maximum servo angle.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM port in the module the servo is plugged into
+ */
+float GetServoMaxAngle(UINT32 slot, UINT32 channel)
+{
+ Servo *servo = (Servo *) AllocatePWM(slot, channel, CreateServoStatic);
+ return servo->GetMaxAngle();
+}
+
+/**
+ * Get the minimum servo angle.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM port in the module the servo is plugged into
+ */
+float GetServoMinAngle(UINT32 slot, UINT32 channel)
+{
+ Servo *servo = (Servo *) AllocatePWM(slot, channel, CreateServoStatic);
+ return servo->GetMinAngle();
+}
+
+/**
+ * Set the servo position.
+ *
+ * Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
+ *
+ * @param channel The PWM port in the module the servo is plugged into
+ * @param value Position from 0.0 to 1.0.
+ */
+void SetServo(UINT32 channel, float value)
+{
+ Servo *servo = (Servo *) AllocatePWM(channel, CreateServoStatic);
+ servo->Set(value);
+}
+
+/**
+ * Get the servo position.
+ *
+ * Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
+ *
+ * @param channel The PWM port in the module the servo is plugged into
+ * @returns Position from 0.0 to 1.0.
+ */
+float GetServo(UINT32 channel)
+{
+ Servo *servo = (Servo *) AllocatePWM(channel, CreateServoStatic);
+ return servo->Get();
+}
+
+/**
+ * Set the servo angle.
+ *
+ * Assume that the servo angle is linear with respect to the PWM value (big assumption, need to test).
+ *
+ * Servo angles that are out of the supported range of the servo simply "saturate" in that direction
+ * In other words, if the servo has a range of (X degrees to Y degrees) than angles of less than X
+ * result in an angle of X being set and angles of more than Y degrees result in an angle of Y being set.
+ *
+ * @param channel The PWM port in the module the servo is plugged into
+ * @param angle The angle in degrees to set the servo.
+ */
+void SetServoAngle(UINT32 channel, float angle)
+{
+ Servo *servo = (Servo *) AllocatePWM(channel, CreateServoStatic);
+ servo->SetAngle(angle);
+}
+
+/**
+ * Get the servo angle.
+ *
+ * Assume that the servo angle is linear with respect to the PWM value (big assumption, need to test).
+ *
+ * @param channel The slot the digital module is plugged into
+ * @return The angle in degrees to which the servo is set.
+ */
+float GetServoAngle(UINT32 channel)
+{
+ Servo *servo = (Servo *) AllocatePWM(channel, CreateServoStatic);
+ return servo->GetAngle();
+}
+
+/**
+ * Get the maximum angle for the servo.
+ *
+ * @param channel The PWM port in the module the servo is plugged into
+ */
+float GetServoMaxAngle(UINT32 channel)
+{
+ Servo *servo = (Servo *) AllocatePWM(channel, CreateServoStatic);
+ return servo->GetMaxAngle();
+}
+
+/**
+ * Get the minimum angle for the servo.
+ *
+ * @param channel The PWM port in the module the servo is plugged into
+ */
+float GetServoMinAngle(UINT32 channel)
+{
+ Servo *servo = (Servo *) AllocatePWM(channel, CreateServoStatic);
+ return servo->GetMinAngle();
+}
+
+/**
+ * Free the resources associated with this Servo object.
+ * The underlying Servo object and the allocated ports are freed.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM port in the module the servo is plugged into
+ */
+void DeleteServo(UINT32 slot, UINT32 channel)
+{
+ Servo *servo = (Servo *) AllocatePWM(slot, channel, CreateServoStatic);
+ DeletePWM(slot, channel);
+ delete servo;
+}
+
+/**
+ * Free the resources associated with this Servo object.
+ * The underlying Servo object and the allocated ports are freed.
+ *
+ * @param channel The PWM port in the module the servo is plugged into
+ */
+void DeleteServo(UINT32 channel)
+{
+ DeleteServo(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+ServoObject CreateServo(UINT32 slot, UINT32 channel)
+{
+ return (ServoObject) new Servo(slot, channel);
+}
+
+ServoObject CreateServo(UINT32 channel)
+{
+ return (ServoObject) new Servo(channel);
+}
+
+void SetServo(ServoObject o, float value)
+{
+ ((Servo *)o)->Set(value);
+}
+
+float GetGetServo(ServoObject o)
+{
+ return ((Servo *)o)->Get();
+}
+
+void SetServoAngle(ServoObject o, float angle)
+{
+ ((Servo *)o)->SetAngle(angle);
+}
+
+float GetServoAngle(ServoObject o)
+{
+ return ((Servo *)o)->GetAngle();
+}
+
+float GetServoMaxAngle(ServoObject o)
+{
+ return ((Servo *)o)->GetMaxAngle();
+}
+
+float GetServoMinAngle(ServoObject o)
+{
+ return ((Servo *)o)->GetMinAngle();
+}
+
+void DeleteServo(ServoObject o)
+{
+ delete (Servo *)o;
+}
+
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CServo.h b/aos/externals/WPILib/WPILib/CInterfaces/CServo.h
new file mode 100644
index 0000000..7010a2f
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CServo.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef C_SERVO_H
+#define C_SERVO_H
+
+void SetServo(UINT32 slot, UINT32 channel, float value);
+float GetGetServo(UINT32 slot, UINT32 channel);
+void SetServoAngle(UINT32 slot, UINT32 channel, float angle);
+float GetServoAngle(UINT32 slot, UINT32 channel);
+float GetServoMaxAngle(UINT32 slot, UINT32 channel);
+float GetServoMinAngle(UINT32 slot, UINT32 channel);
+void SetServo(UINT32 channel, float value);
+float GetGetServo(UINT32 channel);
+void SetServoAngle(UINT32 channel, float angle);
+float GetServoAngle(UINT32 channel);
+float GetServoMaxAngle(UINT32 channel);
+float GetServoMinAngle(UINT32 channel);
+void DeleteServo(UINT32 slot, UINT32 channel);
+void DeleteServo(UINT32 channel);
+
+typedef void *ServoObject;
+
+ServoObject CreateServo(UINT32 slot, UINT32 channel);
+ServoObject CreateServo(UINT32 channel);
+void SetServo(ServoObject o, float value);
+float GetGetServo(ServoObject o);
+void SetServoAngle(ServoObject o, float angle);
+float GetServoAngle(ServoObject o);
+float GetServoMaxAngle(ServoObject o);
+float GetServoMinAngle(ServoObject o);
+void DeleteServo(ServoObject o);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CSolenoid.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CSolenoid.cpp
new file mode 100644
index 0000000..26e3660
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CSolenoid.cpp
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Solenoid.h"
+#include "CInterfaces/CSolenoid.h"
+
+static Solenoid *solenoids[SensorBase::kSolenoidChannels];
+static bool initialized = false;
+
+/**
+ * Internal allocation function for Solenoid channels.
+ * The function is used interally to allocate the Solenoid object and keep track
+ * of the channel mapping to the object for subsequent calls.
+ *
+ * @param channel The channel for the solenoid
+ */
+static Solenoid *allocateSolenoid(UINT32 channel)
+{
+ if (!initialized)
+ {
+ initialized = true;
+ for (unsigned i = 0; i < SensorBase::kSolenoidChannels; i++)
+ solenoids[i] = new Solenoid(i + 1);
+ }
+ if (channel < 1 || channel > SensorBase::kSolenoidChannels)
+ return NULL;
+ return solenoids[channel - 1];
+}
+
+/**
+ * Set the value of a solenoid.
+ *
+ * @param channel The channel on the Solenoid module
+ * @param on Turn the solenoid output off or on.
+ */
+void SetSolenoid(UINT32 channel, bool on)
+{
+ Solenoid *s = allocateSolenoid(channel);
+ if (s != NULL)
+ s->Set(on);
+}
+
+/**
+ * Read the current value of the solenoid.
+ *
+ * @param channel The channel in the Solenoid module
+ * @return The current value of the solenoid.
+ */
+bool GetSolenoid(UINT32 channel)
+{
+ Solenoid *s = allocateSolenoid(channel);
+ if (s == NULL)
+ return false;
+ return s->Get();
+}
+
+/**
+ * Free the resources associated with the Solenoid channel.
+ * Free the resources including the Solenoid object for this channel.
+ *
+ * @param channel The channel in the Solenoid module
+ */
+void DeleteSolenoid(UINT32 channel)
+{
+ if (channel >= 1 && channel <= SensorBase::kSolenoidChannels)
+ {
+ delete solenoids[channel - 1];
+ solenoids[channel - 1] = NULL;
+ }
+}
+
+SolenoidObject CreateSolenoid(UINT32 channel)
+{
+ return (SolenoidObject) new Solenoid(channel);
+}
+
+void DeleteSolenoid(SolenoidObject o)
+{
+ delete (Solenoid *) o;
+}
+
+void SetSolenoid(SolenoidObject o, bool on)
+{
+ ((Solenoid *)o)->Set(on);
+}
+
+bool GetSolenoid(SolenoidObject o)
+{
+ return ((Solenoid *)o)->Get();
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CSolenoid.h b/aos/externals/WPILib/WPILib/CInterfaces/CSolenoid.h
new file mode 100644
index 0000000..739a853
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CSolenoid.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef _C_SOLENOID_H
+#define _C_SOLENOID_H
+
+void SetSolenoid(UINT32 channel, bool on);
+bool GetSolenoid(UINT32 channel);
+
+typedef void *SolenoidObject;
+
+SolenoidObject CreateSolenoid(UINT32 channel);
+void DeleteSolenoid(SolenoidObject o);
+void SetSolenoid(SolenoidObject o, bool on);
+bool GetSolenoid(SolenoidObject o);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CTimer.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CTimer.cpp
new file mode 100644
index 0000000..fef3600
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CTimer.cpp
@@ -0,0 +1,122 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#include "CInterfaces/CTimer.h"
+#include <stdio.h>
+#include "Utility.h"
+
+static Timer *timers[kMaxTimers];
+static bool initialized = false;
+
+/**
+ * Allocate the resources for a timer object
+ * Timers are allocated in an array and indexed with the "index" parameter. There
+ * can be up to 10 timer objects in use at any one time. Deleting a timer object
+ * frees up it's slot and resources.
+ *
+ * @param index The index of this timer object.
+ */
+static Timer *AllocateTimer(UINT32 index)
+{
+ if (!initialized)
+ {
+ for (unsigned i = 0; i < kMaxTimers; i++)
+ timers[i] = NULL;
+ initialized = true;
+ }
+ if (index == 0 || index >= kMaxTimers)
+ {
+ printf("Timer index out of range [1, %d]: %d\n", kMaxTimers, index);
+ return NULL;
+ }
+ Timer *timer = timers[index - 1];
+ if (timer == NULL)
+ {
+ timer = new Timer();
+ timers[index - 1] = timer;
+ }
+ return timer;
+}
+
+/**
+ * Reset the timer by setting the time to 0.
+ *
+ * Make the timer startTime the current time so new requests will be relative now
+ * @param index The index of this timer object.
+ */
+void ResetTimer(UINT32 index)
+{
+ Timer *timer = AllocateTimer(index);
+ if (timer != NULL)
+ {
+ timer->Reset();
+ }
+}
+
+/**
+ * Start the timer running.
+ * Just set the running flag to true indicating that all time requests should be
+ * relative to the system clock.
+ *
+ * @param index The index of this timer object.
+ */
+void StartTimer(UINT32 index)
+{
+ Timer *timer = AllocateTimer(index);
+ if (timer != NULL)
+ {
+ timer->Start();
+ }
+}
+
+/**
+ * Stop the timer.
+ * This computes the time as of now and clears the running flag, causing all
+ * subsequent time requests to be read from the accumulated time rather than
+ * looking at the system clock.
+ *
+ * @param index The index of this timer object.
+ */
+void StopTimer(UINT32 index)
+{
+ Timer *timer = AllocateTimer(index);
+ if (timer != NULL)
+ {
+ timer->Stop();
+ }
+}
+
+/**
+ * Get the current time from the timer. If the clock is running it is derived from
+ * the current system clock the start time stored in the timer class. If the clock
+ * is not running, then return the time when it was last stopped.
+ *
+ * @param index The timer index being used
+ * @return unsigned Current time value for this timer in seconds
+ */
+double GetTimer(UINT32 index)
+{
+ Timer *timer = AllocateTimer(index);
+ if (timer != NULL)
+ {
+ return timer->Get();
+ }
+ else
+ return 0.0;
+}
+
+/**
+ * Free the resources associated with this timer object
+ *
+ * @param index The index of this timer object.
+ */
+void DeleteTimer(UINT32 index)
+{
+ if (index >= 1 && index <= kMaxTimers)
+ {
+ delete timers[index - 1];
+ timers[index - 1] = NULL;
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CTimer.h b/aos/externals/WPILib/WPILib/CInterfaces/CTimer.h
new file mode 100644
index 0000000..bfd756e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CTimer.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#ifndef _C_TIMER_H
+#define _C_TIMER_H
+
+#include "Timer.h"
+
+static const unsigned kMaxTimers = 32;
+
+void ResetTimer(UINT32 index);
+void StartTimer(UINT32 index);
+void StopTimer(UINT32 index);
+double GetTimer(UINT32 index);
+void DeleteTimer(UINT32 index);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CUltrasonic.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CUltrasonic.cpp
new file mode 100644
index 0000000..33c5204
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CUltrasonic.cpp
@@ -0,0 +1,213 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#include "CInterfaces/CUltrasonic.h"
+#include "DigitalModule.h"
+
+static Ultrasonic* ultrasonics[SensorBase::kChassisSlots][SensorBase::kDigitalChannels];
+static bool initialized = false;
+
+/**
+ * Internal routine to allocate and initialize resources for an Ultrasonic sensor
+ * Allocate the actual Ultrasonic sensor object and the slot/channels associated with them. Then
+ * initialize the sensor.
+ *
+ * @param pingSlot The slot for the digital module for the ping connection
+ * @param pingChannel The channel on the digital module for the ping connection
+ * @param echoSlot The slot for the digital module for the echo connection
+ * @param echoChannel The channel on the digital module for the echo connection
+ */
+static void USinit(UINT8 pingModuleNumber, UINT32 pingChannel, UINT8 echoModuleNumber, UINT32 echoChannel)
+{
+ if (!initialized)
+ {
+ initialized = true;
+ for (unsigned i = 0; i < SensorBase::kChassisSlots; i++)
+ for (unsigned j = 0; j < SensorBase::kDigitalChannels; j++)
+ ultrasonics[i][j] = NULL;
+ }
+ if (SensorBase::CheckDigitalModule(pingModuleNumber)
+ && SensorBase::CheckDigitalChannel(pingChannel)
+ && SensorBase::CheckDigitalModule(echoModuleNumber)
+ && SensorBase::CheckDigitalChannel(echoChannel))
+ {
+ if (ultrasonics[pingModuleNumber - 1][pingChannel - 1] == NULL)
+ {
+ ultrasonics[pingModuleNumber - 1][pingChannel - 1] = new Ultrasonic(pingModuleNumber, pingChannel, echoModuleNumber, echoChannel);
+ printf("new Ultrasonic(%d, %d, %d, %d)\n", pingModuleNumber, pingChannel, echoModuleNumber, echoChannel);
+ }
+ Ultrasonic::SetAutomaticMode(true);
+ }
+}
+
+/**
+ * Internal routine to return the pointer to an Ultrasonic sensor
+ * Return the pointer to a previously allocated Ultrasonic sensor object. Only the ping connection
+ * is required since there can only be a single sensor connected to that channel
+ *
+ * @param pingSlot The slot for the digital module for the ping connection
+ * @param pingChannel The channel on the digital module for the ping connection
+ */
+static Ultrasonic *USptr(UINT8 pingModuleNumber, UINT32 pingChannel)
+{
+ if (!SensorBase::CheckDigitalModule(pingModuleNumber) || !SensorBase::CheckDigitalChannel(pingChannel))
+ return NULL;
+ Ultrasonic *us = ultrasonics[pingModuleNumber - 1][pingChannel - 1];
+ return us;
+}
+
+/**
+ * Initialize and Ultrasonic sensor.
+ *
+ * Initialize an Ultrasonic sensor to start it pinging in round robin mode with other allocated
+ * sensors. There is no need to explicitly start the sensor pinging.
+ *
+ * @param pingSlot The slot for the digital module for the ping connection
+ * @param pingChannel The channel on the digital module for the ping connection
+ * @param echoSlot The slot for the digital module for the echo connection
+ * @param echoChannel The channel on the digital module for the echo connection
+ */
+void InitUltrasonic(UINT8 pingModuleNumber, UINT32 pingChannel, UINT8 echoModuleNumber, UINT32 echoChannel)
+{
+ Ultrasonic *us = USptr(pingModuleNumber, pingChannel);
+ if (!us) USinit(pingModuleNumber, pingChannel, echoModuleNumber, echoChannel);
+}
+
+/**
+ * Initialize and Ultrasonic sensor.
+ *
+ * Initialize an Ultrasonic sensor to start it pinging in round robin mode with other allocated
+ * sensors. There is no need to explicitly start the sensor pinging.
+ *
+ * @param pingChannel The channel on the digital module for the ping connection
+ * @param echoChannel The channel on the digital module for the echo connection
+ */
+void InitUltrasonic(UINT32 pingChannel, UINT32 echoChannel)
+{
+ InitUltrasonic(SensorBase::GetDefaultDigitalModule(), pingChannel,
+ SensorBase::GetDefaultDigitalModule(), echoChannel);
+}
+
+/**
+ * Get the range in inches from the ultrasonic sensor.
+ * @return double Range in inches of the target returned from the ultrasonic sensor. If there is
+ * no valid value yet, i.e. at least one measurement hasn't completed, then return 0.
+ *
+ * @param pingSlot The slot for the digital module for the ping connection
+ * @param pingChannel The channel on the digital module for the ping connection
+ * @param echoSlot The slot for the digital module for the echo connection
+ * @param echoChannel The channel on the digital module for the echo connection
+ */
+double GetUltrasonicInches(UINT8 pingModuleNumber, UINT32 pingChannel, UINT8 echoModuleNumber, UINT32 echoChannel)
+{
+ Ultrasonic *us = USptr(pingModuleNumber, pingChannel);
+ if (us != NULL)
+ return us->GetRangeInches();
+ else
+ return 0.0;
+}
+
+/**
+ * Get the range in inches from the ultrasonic sensor.
+ * @return double Range in inches of the target returned from the ultrasonic sensor. If there is
+ * no valid value yet, i.e. at least one measurement hasn't completed, then return 0.
+ *
+ * @param pingChannel The channel on the digital module for the ping connection
+ * @param echoChannel The channel on the digital module for the echo connection
+ */
+double GetUltrasonicInches(UINT32 pingChannel, UINT32 echoChannel)
+{
+ return GetUltrasonicInches(SensorBase::GetDefaultDigitalModule(), pingChannel,
+ SensorBase::GetDefaultDigitalModule(), echoChannel);
+}
+
+/**
+ * Get the range in millimeters from the ultrasonic sensor.
+ * @return double Range in millimeters of the target returned by the ultrasonic sensor.
+ * If there is no valid value yet, i.e. at least one measurement hasn't complted, then return 0.
+ *
+ * @param pingSlot The slot for the digital module for the ping connection
+ * @param pingChannel The channel on the digital module for the ping connection
+ * @param echoSlot The slot for the digital module for the echo connection
+ * @param echoChannel The channel on the digital module for the echo connection
+ */
+double GetUltrasonicMM(UINT8 pingModuleNumber, UINT32 pingChannel, UINT8 echoModuleNumber, UINT32 echoChannel)
+{
+ Ultrasonic *us = USptr(pingModuleNumber, pingChannel);
+ if (us != NULL)
+ return us->GetRangeMM();
+ else
+ return 0.0;
+}
+
+/**
+ * Get the range in millimeters from the ultrasonic sensor.
+ * @return double Range in millimeters of the target returned by the ultrasonic sensor.
+ * If there is no valid value yet, i.e. at least one measurement hasn't complted, then return 0.
+ *
+ * @param pingChannel The channel on the digital module for the ping connection
+ * @param echoChannel The channel on the digital module for the echo connection
+ */
+double GetUltrasonicMM(UINT32 pingChannel, UINT32 echoChannel)
+{
+ return GetUltrasonicMM(SensorBase::GetDefaultDigitalModule(), pingChannel,
+ SensorBase::GetDefaultDigitalModule(), echoChannel);
+}
+
+/**
+ * Free the resources associated with an ultrasonic sensor.
+ * Deallocate the Ultrasonic object and free the associated resources.
+ *
+ * @param pingSlot The slot for the digital module for the ping connection
+ * @param pingChannel The channel on the digital module for the ping connection
+ * @param echoSlot The slot for the digital module for the echo connection
+ * @param echoChannel The channel on the digital module for the echo connection
+ */
+void DeleteUltrasonic(UINT8 pingModuleNumber, UINT32 pingChannel, UINT8 echoModuleNumber, UINT32 echoChannel)
+{
+ if (SensorBase::CheckDigitalModule(pingModuleNumber) && SensorBase::CheckDigitalChannel(pingChannel))
+ {
+ delete ultrasonics[pingModuleNumber - 1][pingChannel - 1];
+ ultrasonics[pingModuleNumber - 1][pingChannel - 1] = NULL;
+ }
+}
+
+/**
+ * Free the resources associated with an ultrasonic sensor.
+ * Deallocate the Ultrasonic object and free the associated resources.
+ *
+ * @param pingChannel The channel on the digital module for the ping connection
+ * @param echoChannel The channel on the digital module for the echo connection
+ */
+void DeleteUltrasonic(UINT32 pingChannel, UINT32 echoChannel)
+{
+ DeleteUltrasonic(SensorBase::GetDefaultDigitalModule(), pingChannel, SensorBase::GetDefaultDigitalModule(), echoChannel);
+}
+
+UltrasonicObject CreateUltrasonic(UINT32 pingChannel, UINT32 echoChannel)
+{
+ return (UltrasonicObject) new Ultrasonic(pingChannel, echoChannel);
+}
+
+UltrasonicObject CreateUltrasonic(UINT8 pingModuleNumber, UINT32 pingChannel, UINT8 echoModuleNumber, UINT32 echoChannel)
+{
+ return (UltrasonicObject) new Ultrasonic(pingModuleNumber, pingChannel, echoModuleNumber, echoChannel);
+}
+
+double GetUltrasonicInches(UltrasonicObject o)
+{
+ return ((Ultrasonic *)o)->GetRangeInches();
+}
+
+double GetUltrasonicMM(UltrasonicObject o)
+{
+ return ((Ultrasonic *)o)->GetRangeMM();
+}
+
+void DeleteUltrasonic(UltrasonicObject o)
+{
+ delete (Ultrasonic *) o;
+}
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CUltrasonic.h b/aos/externals/WPILib/WPILib/CInterfaces/CUltrasonic.h
new file mode 100644
index 0000000..5faa145
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CUltrasonic.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#ifndef C_ULTRASONIC_H
+#define C_ULTRASONIC_H
+
+#include "Ultrasonic.h"
+
+void InitUltrasonic(UINT32 pingChannel, UINT32 echoChannel);
+void InitUltrasonic(UINT8 pingModuleNumber, UINT32 pingChannel, UINT8 echoModuleNumber, UINT32 echoChannel);
+double GetUltrasonicInches(UINT32 pingChannel, UINT32 echoChannel);
+double GetUltrasonicInches(UINT8 pingModuleNumber, UINT32 pingChannel, UINT8 echoModuleNumber, UINT32 echoChannel);
+double GetUltrasonicMM(UINT32 pingChannel, UINT32 echoChannel);
+double GetUltrasonicMM(UINT8 pingModuleNumber, UINT32 pingChannel, UINT8 echoModuleNumber, UINT32 echoChannel);
+void DeleteUltrasonic(UINT32 pingChannel, UINT32 echoChannel);
+void DeleteUltrasonic(UINT8 pingModuleNumber, UINT32 pingChannel, UINT8 echoModuleNumber, UINT32 echoChannel);
+
+typedef void *UltrasonicObject;
+
+UltrasonicObject CreateUltrasonic(UINT32 pingChannel, UINT32 echoChannel);
+UltrasonicObject CreateUltrasonic(UINT8 pingModuleNumber, UINT32 pingChannel, UINT8 echoModuleNumber, UINT32 echoChannel);
+double GetUltrasonicInches(UltrasonicObject o);
+double GetUltrasonicMM(UltrasonicObject o);
+void DeleteUltrasonic(UltrasonicObject o);
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CVictor.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CVictor.cpp
new file mode 100644
index 0000000..389c30f
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CVictor.cpp
@@ -0,0 +1,177 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "CInterfaces/CVictor.h"
+#include "CInterfaces/CPWM.h"
+#include "Victor.h"
+
+/**
+ * Create an instance of a Victor object (used internally by this module)
+ *
+ * @param slot The slot that the digital module is plugged into
+ * @param channel The PWM channel that the motor is plugged into
+ */
+static SensorBase *CreateVictorStatic(UINT32 slot, UINT32 channel)
+{
+ return new Victor(slot, channel);
+}
+
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel used for this Victor
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ */
+void SetVictorSpeed(UINT32 slot, UINT32 channel, float speed)
+{
+ Victor *victor = (Victor *) AllocatePWM(slot, channel, CreateVictorStatic);
+ if (victor) victor->Set(speed);
+}
+
+/**
+ * Set the PWM value directly to the hardware.
+ *
+ * Write a raw value to a PWM channel.
+ *
+ * @param channel The PWM channel used for this Victor
+ * @param value Raw PWM value. Range 0 - 255.
+ */
+void SetVictorRaw(UINT32 channel, UINT8 value)
+{
+ Victor *victor = (Victor *) AllocatePWM(channel, CreateVictorStatic);
+ if (victor) victor->SetRaw(value);
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param channel The PWM channel used for this Victor
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ */
+void SetVictorSpeed(UINT32 channel, float speed)
+{
+ Victor *victor = (Victor *) AllocatePWM(channel, CreateVictorStatic);
+ if (victor) victor->Set(speed);
+}
+
+/**
+ * Get the PWM value directly from the hardware.
+ *
+ * Read a raw value from a PWM channel.
+ *
+ * @param channel The PWM channel used for this Victor
+ * @return Raw PWM control value. Range: 0 - 255.
+ */
+UINT8 GetVictorRaw(UINT32 channel)
+{
+ Victor *victor = (Victor *) AllocatePWM(channel, CreateVictorStatic);
+ if (victor)
+ return victor->GetRaw();
+ else
+ return 0;
+}
+
+/**
+ * Set the PWM value directly to the hardware.
+ *
+ * Write a raw value to a PWM channel.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel used for this Victor
+ * @param value Raw PWM value. Range 0 - 255.
+ */
+void SetVictorRaw(UINT32 slot, UINT32 channel, UINT8 value)
+{
+ Victor *victor = (Victor *) AllocatePWM(slot, channel, CreateVictorStatic);
+ if (victor) victor->SetRaw(value);
+}
+
+
+/**
+ * Get the PWM value directly from the hardware.
+ *
+ * Read a raw value from a PWM channel.
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel used for this Victor
+ * @return Raw PWM control value. Range: 0 - 255.
+ */
+UINT8 GetVictorRaw(UINT32 slot, UINT32 channel)
+{
+ Victor *victor = (Victor *) AllocatePWM(slot, channel, CreateVictorStatic);
+ if (victor)
+ return victor->GetRaw();
+ else
+ return 0;
+}
+
+/**
+ * Delete resources for a Victor
+ * Free the underlying object and delete the allocated resources for the Victor
+ *
+ * @param slot The slot the digital module is plugged into
+ * @param channel The PWM channel used for this Victor
+ */
+void DeleteVictor(UINT32 slot, UINT32 channel)
+{
+ Victor *victor = (Victor *) AllocatePWM(slot, channel, CreateVictorStatic);
+ delete victor;
+ DeletePWM(slot, channel);
+}
+
+/**
+ * Delete resources for a Victor
+ * Free the underlying object and delete the allocated resources for the Victor
+ *
+ * @param channel The PWM channel used for this Victor
+ */
+void DeleteVictor(UINT32 channel)
+{
+ DeleteVictor(SensorBase::GetDefaultDigitalModule(), channel);
+}
+
+VictorObject CreateVictor(UINT32 slot, UINT32 channel)
+{
+ return (VictorObject) new Victor(slot, channel);
+}
+
+VictorObject CreateVictor(UINT32 channel)
+{
+ return (VictorObject) new Victor(channel);
+}
+
+void DeleteVictor(VictorObject o)
+{
+ delete (Victor *) o;
+}
+
+void SetVictorSpeed(VictorObject o, float speed)
+{
+ ((Victor *)o)->Set(speed);
+}
+
+void SetVictorRaw(VictorObject o, UINT8 value)
+{
+ ((Victor *)o)->SetRaw(value);
+}
+
+UINT8 GetVictorRaw(VictorObject o)
+{
+ return ((Victor *)o)->GetRaw();
+}
+
+void LoadVictor()
+{
+}
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CVictor.h b/aos/externals/WPILib/WPILib/CInterfaces/CVictor.h
new file mode 100644
index 0000000..2080b97
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CVictor.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef C_VICTOR_H
+#define C_VICTOR_H
+
+#include <VxWorks.h>
+
+void SetVictorSpeed(UINT32 module, UINT32 channel, float speed);
+void SetVictorSpeed(UINT32 channel, float speed);
+void SetVictorRaw(UINT32 channel, UINT8 value);
+UINT8 GetVictorRaw(UINT32 channel);
+void SetVictorRaw(UINT32 module, UINT32 channel, UINT8 value);
+UINT8 GetVictorRaw(UINT32 module, UINT32 channel);
+void DeleteVictor(UINT32 module, UINT32 channel);
+void DeleteVictor(UINT32 channel);
+
+typedef void *VictorObject;
+
+VictorObject CreateVictor(UINT32 slot, UINT32 channel);
+VictorObject CreateVictor(UINT32 channel);
+void DeleteVictor(VictorObject o);
+void SetVictorSpeed(VictorObject o, float speed);
+void SetVictorRaw(VictorObject o, UINT8 value);
+UINT8 GetVictorRaw(VictorObject o);
+
+void LoadVictor();
+#endif
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CWatchdog.cpp b/aos/externals/WPILib/WPILib/CInterfaces/CWatchdog.cpp
new file mode 100644
index 0000000..efe2061
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CWatchdog.cpp
@@ -0,0 +1,61 @@
+#include "CInterfaces/CWatchdog.h"
+#include "Watchdog.h"
+
+WatchdogObject CreateWatchdog()
+{
+ return (WatchdogObject) new Watchdog();
+}
+
+void DeleteWatchdog(WatchdogObject o)
+{
+ delete (Watchdog *) o;
+}
+
+bool FeedWatchdog(WatchdogObject o)
+{
+ return ((Watchdog *)o)->Feed();
+}
+
+void KillWatchdog(WatchdogObject o)
+{
+ ((Watchdog *)o)->Kill();
+}
+
+double GetWatchdogTimer(WatchdogObject o)
+{
+ return ((Watchdog *)o)->GetTimer();
+}
+
+double GetWatchdogExpiration(WatchdogObject o)
+{
+ return ((Watchdog *)o)->GetExpiration();
+}
+
+void SetWatchdogExpiration(WatchdogObject o, double expiration)
+{
+ ((Watchdog *)o)->SetExpiration(expiration);
+}
+
+bool GetWatchdogEnabled(WatchdogObject o)
+{
+ return ((Watchdog *)o)->GetEnabled();
+}
+
+void SetWatchdogEnabled(WatchdogObject o, bool enabled)
+{
+ ((Watchdog *)o)->SetEnabled(enabled);
+}
+
+bool IsWatchdogAlive(WatchdogObject o)
+{
+ return ((Watchdog *)o)->IsAlive();
+}
+
+bool IsWatchdogSystemActive(WatchdogObject o)
+{
+ return ((Watchdog *)o)->IsSystemActive();
+}
+
+void LoadWatchdog()
+{
+}
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CWatchdog.h b/aos/externals/WPILib/WPILib/CInterfaces/CWatchdog.h
new file mode 100644
index 0000000..4f33c15
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CWatchdog.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef C_WATCHDOG_H
+#define C_WATCHDOG_H
+
+typedef void *WatchdogObject;
+
+WatchdogObject CreateWatchdog();
+void DeleteWatchdog(WatchdogObject o);
+bool FeedWatchdog(WatchdogObject o);
+void KillWatchdog(WatchdogObject o);
+double GetWatchdogTimer(WatchdogObject o);
+double GetWatchdogExpiration(WatchdogObject o);
+void SetWatchdogExpiration(WatchdogObject o, double expiration);
+bool GetWatchdogEnabled(WatchdogObject o);
+void SetWatchdogEnabled(WatchdogObject o, bool enabled);
+bool IsWatchdogAlive(WatchdogObject o);
+bool IsWatchdogSystemActive(WatchdogObject o);
+
+void LoadWatchdog();
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/CWrappers.h b/aos/externals/WPILib/WPILib/CInterfaces/CWrappers.h
new file mode 100644
index 0000000..0bb96b5
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/CWrappers.h
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef C_WRAPPERS_H
+#define C_WRAPPERS_H
+
+class SensorBase;
+typedef SensorBase *(*SensorCreator)(UINT32 slot, UINT32 channel);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/Doxyfile b/aos/externals/WPILib/WPILib/CInterfaces/Doxyfile
new file mode 100644
index 0000000..9eada45
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/Doxyfile
@@ -0,0 +1,253 @@
+# Doxyfile 1.5.7.1
+
+#---------------------------------------------------------------------------
+# Project related configuration options
+#---------------------------------------------------------------------------
+DOXYFILE_ENCODING = UTF-8
+PROJECT_NAME = "WPILib C Reference Manual"
+PROJECT_NUMBER = "Version 1.0"
+OUTPUT_DIRECTORY = /Users/brad/Documents/WPILibDocs/CInterfaces
+CREATE_SUBDIRS = NO
+OUTPUT_LANGUAGE = English
+BRIEF_MEMBER_DESC = YES
+REPEAT_BRIEF = YES
+ABBREVIATE_BRIEF =
+ALWAYS_DETAILED_SEC = NO
+INLINE_INHERITED_MEMB = NO
+FULL_PATH_NAMES = YES
+STRIP_FROM_PATH =
+STRIP_FROM_INC_PATH =
+SHORT_NAMES = NO
+JAVADOC_AUTOBRIEF = NO
+QT_AUTOBRIEF = NO
+MULTILINE_CPP_IS_BRIEF = NO
+INHERIT_DOCS = YES
+SEPARATE_MEMBER_PAGES = NO
+TAB_SIZE = 8
+ALIASES =
+OPTIMIZE_OUTPUT_FOR_C = YES
+OPTIMIZE_OUTPUT_JAVA = NO
+OPTIMIZE_FOR_FORTRAN = NO
+OPTIMIZE_OUTPUT_VHDL = NO
+BUILTIN_STL_SUPPORT = NO
+CPP_CLI_SUPPORT = NO
+SIP_SUPPORT = NO
+IDL_PROPERTY_SUPPORT = YES
+DISTRIBUTE_GROUP_DOC = NO
+SUBGROUPING = YES
+TYPEDEF_HIDES_STRUCT = NO
+SYMBOL_CACHE_SIZE = 0
+#---------------------------------------------------------------------------
+# Build related configuration options
+#---------------------------------------------------------------------------
+EXTRACT_ALL = YES
+EXTRACT_PRIVATE = YES
+EXTRACT_STATIC = YES
+EXTRACT_LOCAL_CLASSES = YES
+EXTRACT_LOCAL_METHODS = NO
+EXTRACT_ANON_NSPACES = NO
+HIDE_UNDOC_MEMBERS = NO
+HIDE_UNDOC_CLASSES = NO
+HIDE_FRIEND_COMPOUNDS = NO
+HIDE_IN_BODY_DOCS = NO
+INTERNAL_DOCS = NO
+CASE_SENSE_NAMES = NO
+HIDE_SCOPE_NAMES = NO
+SHOW_INCLUDE_FILES = YES
+INLINE_INFO = YES
+SORT_MEMBER_DOCS = YES
+SORT_BRIEF_DOCS = NO
+SORT_GROUP_NAMES = NO
+SORT_BY_SCOPE_NAME = NO
+GENERATE_TODOLIST = YES
+GENERATE_TESTLIST = YES
+GENERATE_BUGLIST = YES
+GENERATE_DEPRECATEDLIST= YES
+ENABLED_SECTIONS =
+MAX_INITIALIZER_LINES = 30
+SHOW_USED_FILES = YES
+SHOW_DIRECTORIES = NO
+SHOW_FILES = YES
+SHOW_NAMESPACES = YES
+FILE_VERSION_FILTER =
+LAYOUT_FILE =
+#---------------------------------------------------------------------------
+# configuration options related to warning and progress messages
+#---------------------------------------------------------------------------
+QUIET = NO
+WARNINGS = YES
+WARN_IF_UNDOCUMENTED = YES
+WARN_IF_DOC_ERROR = YES
+WARN_NO_PARAMDOC = NO
+WARN_FORMAT = "$file:$line: $text"
+WARN_LOGFILE =
+#---------------------------------------------------------------------------
+# configuration options related to the input files
+#---------------------------------------------------------------------------
+INPUT = /Users/brad/Documents/workspace/WPILib/CInterfaces
+INPUT_ENCODING = UTF-8
+FILE_PATTERNS =
+RECURSIVE = NO
+EXCLUDE =
+EXCLUDE_SYMLINKS = NO
+EXCLUDE_PATTERNS =
+EXCLUDE_SYMBOLS =
+EXAMPLE_PATH =
+EXAMPLE_PATTERNS =
+EXAMPLE_RECURSIVE = NO
+IMAGE_PATH =
+INPUT_FILTER =
+FILTER_PATTERNS =
+FILTER_SOURCE_FILES = NO
+#---------------------------------------------------------------------------
+# configuration options related to source browsing
+#---------------------------------------------------------------------------
+SOURCE_BROWSER = NO
+INLINE_SOURCES = NO
+STRIP_CODE_COMMENTS = YES
+REFERENCED_BY_RELATION = NO
+REFERENCES_RELATION = NO
+REFERENCES_LINK_SOURCE = YES
+USE_HTAGS = NO
+VERBATIM_HEADERS = NO
+#---------------------------------------------------------------------------
+# configuration options related to the alphabetical class index
+#---------------------------------------------------------------------------
+ALPHABETICAL_INDEX = NO
+COLS_IN_ALPHA_INDEX = 5
+IGNORE_PREFIX =
+#---------------------------------------------------------------------------
+# configuration options related to the HTML output
+#---------------------------------------------------------------------------
+GENERATE_HTML = NO
+HTML_OUTPUT = html
+HTML_FILE_EXTENSION = .html
+HTML_HEADER =
+HTML_FOOTER =
+HTML_STYLESHEET =
+HTML_ALIGN_MEMBERS = YES
+HTML_DYNAMIC_SECTIONS = NO
+GENERATE_DOCSET = NO
+DOCSET_FEEDNAME = "Doxygen generated docs"
+DOCSET_BUNDLE_ID = org.doxygen.Project
+GENERATE_HTMLHELP = NO
+CHM_FILE =
+HHC_LOCATION =
+GENERATE_CHI = NO
+CHM_INDEX_ENCODING =
+BINARY_TOC = NO
+TOC_EXPAND = NO
+GENERATE_QHP = NO
+QCH_FILE =
+QHP_NAMESPACE = org.doxygen.Project
+QHP_VIRTUAL_FOLDER = doc
+QHG_LOCATION =
+DISABLE_INDEX = NO
+ENUM_VALUES_PER_LINE = 4
+GENERATE_TREEVIEW = NONE
+TREEVIEW_WIDTH = 250
+FORMULA_FONTSIZE = 10
+#---------------------------------------------------------------------------
+# configuration options related to the LaTeX output
+#---------------------------------------------------------------------------
+GENERATE_LATEX = YES
+LATEX_OUTPUT = latex
+LATEX_CMD_NAME = latex
+MAKEINDEX_CMD_NAME = makeindex
+COMPACT_LATEX = NO
+PAPER_TYPE = a4wide
+EXTRA_PACKAGES =
+LATEX_HEADER =
+PDF_HYPERLINKS = YES
+USE_PDFLATEX = YES
+LATEX_BATCHMODE = NO
+LATEX_HIDE_INDICES = NO
+#---------------------------------------------------------------------------
+# configuration options related to the RTF output
+#---------------------------------------------------------------------------
+GENERATE_RTF = NO
+RTF_OUTPUT = rtf
+COMPACT_RTF = NO
+RTF_HYPERLINKS = NO
+RTF_STYLESHEET_FILE =
+RTF_EXTENSIONS_FILE =
+#---------------------------------------------------------------------------
+# configuration options related to the man page output
+#---------------------------------------------------------------------------
+GENERATE_MAN = NO
+MAN_OUTPUT = man
+MAN_EXTENSION = .3
+MAN_LINKS = NO
+#---------------------------------------------------------------------------
+# configuration options related to the XML output
+#---------------------------------------------------------------------------
+GENERATE_XML = NO
+XML_OUTPUT = xml
+XML_SCHEMA =
+XML_DTD =
+XML_PROGRAMLISTING = YES
+#---------------------------------------------------------------------------
+# configuration options for the AutoGen Definitions output
+#---------------------------------------------------------------------------
+GENERATE_AUTOGEN_DEF = NO
+#---------------------------------------------------------------------------
+# configuration options related to the Perl module output
+#---------------------------------------------------------------------------
+GENERATE_PERLMOD = NO
+PERLMOD_LATEX = NO
+PERLMOD_PRETTY = YES
+PERLMOD_MAKEVAR_PREFIX =
+#---------------------------------------------------------------------------
+# Configuration options related to the preprocessor
+#---------------------------------------------------------------------------
+ENABLE_PREPROCESSING = YES
+MACRO_EXPANSION = NO
+EXPAND_ONLY_PREDEF = NO
+SEARCH_INCLUDES = YES
+INCLUDE_PATH =
+INCLUDE_FILE_PATTERNS =
+PREDEFINED =
+EXPAND_AS_DEFINED =
+SKIP_FUNCTION_MACROS = YES
+#---------------------------------------------------------------------------
+# Configuration::additions related to external references
+#---------------------------------------------------------------------------
+TAGFILES =
+GENERATE_TAGFILE =
+ALLEXTERNALS = NO
+EXTERNAL_GROUPS = YES
+PERL_PATH = /usr/bin/perl
+#---------------------------------------------------------------------------
+# Configuration options related to the dot tool
+#---------------------------------------------------------------------------
+CLASS_DIAGRAMS = NO
+MSCGEN_PATH = /Applications/Doxygen.app/Contents/Resources/
+HIDE_UNDOC_RELATIONS = YES
+HAVE_DOT = NO
+DOT_FONTNAME = FreeSans
+DOT_FONTSIZE = 10
+DOT_FONTPATH =
+CLASS_GRAPH = YES
+COLLABORATION_GRAPH = YES
+GROUP_GRAPHS = YES
+UML_LOOK = NO
+TEMPLATE_RELATIONS = NO
+INCLUDE_GRAPH = YES
+INCLUDED_BY_GRAPH = YES
+CALL_GRAPH = NO
+CALLER_GRAPH = NO
+GRAPHICAL_HIERARCHY = YES
+DIRECTORY_GRAPH = YES
+DOT_IMAGE_FORMAT = png
+DOT_PATH =
+DOTFILE_DIRS =
+DOT_GRAPH_MAX_NODES = 50
+MAX_DOT_GRAPH_DEPTH = 0
+DOT_TRANSPARENT = NO
+DOT_MULTI_TARGETS = NO
+GENERATE_LEGEND = YES
+DOT_CLEANUP = YES
+#---------------------------------------------------------------------------
+# Configuration::additions related to the search engine
+#---------------------------------------------------------------------------
+SEARCHENGINE = NO
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/Makefile b/aos/externals/WPILib/WPILib/CInterfaces/Makefile
new file mode 100644
index 0000000..dd8ec83
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/Makefile
@@ -0,0 +1,2404 @@
+# Wind River Workbench generated Makefile.
+# Do not edit!!!
+#
+# The file ".wrmakefile" is the template used by the Wind River Workbench to
+# generate the makefiles of this project. Add user-specific build targets and
+# make rules only(!) in this project's ".wrmakefile" file. These will then be
+# automatically dumped into the makefiles.
+
+WIND_HOME := $(subst \,/,$(WIND_HOME))
+WIND_BASE := $(subst \,/,$(WIND_BASE))
+WIND_USR := $(subst \,/,$(WIND_USR))
+
+all : pre_build main_all post_build
+
+_clean ::
+ @echo "make: removing targets and objects of `pwd`"
+
+TRACE=0
+TRACEON=$(TRACE:0=@)
+TRACE_FLAG=$(TRACEON:1=)
+
+MAKEFILE := Makefile
+
+BUILD_SPEC = PPC603gnu
+DEBUG_MODE = 1
+SRC_DIR := .
+BUILD_ROOT_DIR :=
+PRJ_ROOT_DIR := C:/windriver/workspace/WPILib
+WS_ROOT_DIR := C:/windriver/workspace
+
+ALL_BUILD_SPECS := PPC32diab PPC32gnu PPC32sfdiab PPC32sfgnu \
+ PPC403diab PPC403gnu PPC405diab PPC405gnu \
+ PPC405sfdiab PPC405sfgnu PPC440diab PPC440gnu \
+ PPC440sfdiab PPC440sfgnu PPC603diab PPC603gnu \
+ PPC604diab PPC604gnu PPC85XXdiab PPC85XXgnu \
+ PPC85XXsfdiab PPC85XXsfgnu PPC860sfdiab PPC860sfgnu \
+ SIMLINUXdiab SIMLINUXgnu SIMNTdiab SIMNTgnu \
+ SIMSPARCSOLARISdiab SIMSPARCSOLARISgnu
+ENABLED_BUILD_SPECS := PPC603gnu
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32diab_DEBUG
+else
+OBJ_DIR := PPC32diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32gnu_DEBUG
+else
+OBJ_DIR := PPC32gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfdiab_DEBUG
+else
+OBJ_DIR := PPC32sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfgnu_DEBUG
+else
+OBJ_DIR := PPC32sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403diab_DEBUG
+else
+OBJ_DIR := PPC403diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403gnu_DEBUG
+else
+OBJ_DIR := PPC403gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405diab_DEBUG
+else
+OBJ_DIR := PPC405diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405gnu_DEBUG
+else
+OBJ_DIR := PPC405gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfdiab_DEBUG
+else
+OBJ_DIR := PPC405sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfgnu_DEBUG
+else
+OBJ_DIR := PPC405sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440diab_DEBUG
+else
+OBJ_DIR := PPC440diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440gnu_DEBUG
+else
+OBJ_DIR := PPC440gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfdiab_DEBUG
+else
+OBJ_DIR := PPC440sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfgnu_DEBUG
+else
+OBJ_DIR := PPC440sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603diab_DEBUG
+else
+OBJ_DIR := PPC603diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603gnu_DEBUG
+else
+OBJ_DIR := PPC603gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604diab_DEBUG
+else
+OBJ_DIR := PPC604diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604gnu_DEBUG
+else
+OBJ_DIR := PPC604gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXdiab_DEBUG
+else
+OBJ_DIR := PPC85XXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXgnu_DEBUG
+else
+OBJ_DIR := PPC85XXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfdiab_DEBUG
+else
+OBJ_DIR := PPC85XXsfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfgnu_DEBUG
+else
+OBJ_DIR := PPC85XXsfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfdiab_DEBUG
+else
+OBJ_DIR := PPC860sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfgnu_DEBUG
+else
+OBJ_DIR := PPC860sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXdiab_DEBUG
+else
+OBJ_DIR := SIMLINUXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXgnu_DEBUG
+else
+OBJ_DIR := SIMLINUXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTdiab_DEBUG
+else
+OBJ_DIR := SIMNTdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTgnu_DEBUG
+else
+OBJ_DIR := SIMNTgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISdiab_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISgnu_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISgnu
+endif
+endif
+
+DEP_FILES := $(OBJ_DIR)/CAnalogChannel.d $(OBJ_DIR)/CCounter.d $(OBJ_DIR)/CWatchdog.d \
+ $(OBJ_DIR)/SimpleCRobot.d $(OBJ_DIR)/CAccelerometer.d $(OBJ_DIR)/CJoystick.d \
+ $(OBJ_DIR)/CTimer.d $(OBJ_DIR)/CCompressor.d $(OBJ_DIR)/CRobotDrive.d \
+ $(OBJ_DIR)/CDigitalInput.d $(OBJ_DIR)/CGearTooth.d $(OBJ_DIR)/CGyro.d \
+ $(OBJ_DIR)/CDigitalOutput.d $(OBJ_DIR)/CSolenoid.d $(OBJ_DIR)/CSerialPort.d \
+ $(OBJ_DIR)/CRelay.d $(OBJ_DIR)/CDriverStation.d $(OBJ_DIR)/CVictor.d \
+ $(OBJ_DIR)/CPWM.d $(OBJ_DIR)/CEncoder.d $(OBJ_DIR)/CUltrasonic.d \
+ $(OBJ_DIR)/CJaguar.d $(OBJ_DIR)/CServo.d
+-include $(DEP_FILES)
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+SUBDIRS :=
+OBJECTS := $(OBJ_DIR)/CAnalogChannel.o $(OBJ_DIR)/CCounter.o $(OBJ_DIR)/CWatchdog.o \
+ $(OBJ_DIR)/SimpleCRobot.o $(OBJ_DIR)/CAccelerometer.o $(OBJ_DIR)/CJoystick.o \
+ $(OBJ_DIR)/CTimer.o $(OBJ_DIR)/CCompressor.o $(OBJ_DIR)/CRobotDrive.o \
+ $(OBJ_DIR)/CDigitalInput.o $(OBJ_DIR)/CGearTooth.o $(OBJ_DIR)/CGyro.o \
+ $(OBJ_DIR)/CDigitalOutput.o $(OBJ_DIR)/CSolenoid.o $(OBJ_DIR)/CSerialPort.o \
+ $(OBJ_DIR)/CRelay.o $(OBJ_DIR)/CDriverStation.o $(OBJ_DIR)/CVictor.o \
+ $(OBJ_DIR)/CPWM.o $(OBJ_DIR)/CEncoder.o $(OBJ_DIR)/CUltrasonic.o \
+ $(OBJ_DIR)/CJaguar.o $(OBJ_DIR)/CServo.o
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+
+PROJECT_TYPE = DKM
+DEFINES =
+EXPAND_DBG = 0
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFH:vxworks63 -Xstmw-slow -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mhard-float -mstrict-align -mno-implicit-fp -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -msoft-float -mstrict-align
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC403FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=403 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC603FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=603 -mstrict-align -mno-implicit-fp -mlongcall
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I.. -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC604FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=604 -mstrict-align -mno-implicit-fp
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC860FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=860 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tSPARCFH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC =
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+
+
+
+
+
+-include $(PRJ_ROOT_DIR)/*.makefile
+
+-include *.makefile
+
+main_all : external_build $(PROJECT_TARGETS)
+ @echo "make: built targets of `pwd`"
+
+# entry point for extending the build
+external_build ::
+ @echo ""
+
+# main entry point for pre processing prior to the build
+pre_build :: $(PRE_BUILD_STEP) generate_sources
+ @echo ""
+
+# entry point for generating sources prior to the build
+generate_sources ::
+ @echo ""
+
+# main entry point for post processing after the build
+post_build :: $(POST_BUILD_STEP) deploy_output
+ @echo ""
+
+# entry point for deploying output after the build
+deploy_output ::
+ @echo ""
+
+clean :: external_clean $(CLEAN_STEP) _clean
+
+# entry point for extending the build clean
+external_clean ::
+ @echo ""
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/SimpleCRobot.cpp b/aos/externals/WPILib/WPILib/CInterfaces/SimpleCRobot.cpp
new file mode 100644
index 0000000..a4a57a9
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/SimpleCRobot.cpp
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "CInterfaces/SimpleCRobot.h"
+
+#include "Timer.h"
+#include "Utility.h"
+
+static SimpleCRobot *simpleCRobot = NULL;
+
+/**
+ * The simple robot constructor.
+ * The constructor, besides doing the normal constructor stuff, also calls the
+ * Initialize() C function where sensors can be set up immediately after the power
+ * is turned on.
+ */
+SimpleCRobot::SimpleCRobot()
+{
+ simpleCRobot = this;
+ Initialize();
+}
+
+/**
+ * Start a competition.
+ * This code needs to track the order of the field starting to ensure that everything happens
+ * in the right order. Repeatedly run the correct method, either Autonomous or OperatorControl
+ * when the robot is enabled. After running the correct method, wait for some state to change,
+ * either the other mode starts or the robot is disabled. Then go back and wait for the robot
+ * to be enabled again.
+ */
+void SimpleCRobot::StartCompetition()
+{
+ while (1)
+ {
+ while (IsDisabled()) Wait(.01); // wait for robot to be enabled
+
+ if (IsAutonomous())
+ {
+ Autonomous(); // run the autonomous method
+ while (IsAutonomous() && !IsDisabled()) Wait(.01);
+ }
+ else
+ {
+ OperatorControl(); // run the operator control method
+ while (IsOperatorControl() && !IsDisabled()) Wait(.01);
+ }
+ }
+}
+
+bool IsAutonomous()
+{
+ wpi_assert(simpleCRobot != NULL);
+ return simpleCRobot->IsAutonomous();
+}
+
+bool IsOperatorControl()
+{
+ wpi_assert(simpleCRobot != NULL);
+ return simpleCRobot->IsOperatorControl();
+}
+
+bool IsDisabled()
+{
+ wpi_assert(simpleCRobot != NULL);
+ return simpleCRobot->IsDisabled();
+}
+
+void SetWatchdogEnabled(bool enable)
+{
+ simpleCRobot->GetWatchdog().SetEnabled(enable);
+}
+
+void SetWatchdogExpiration(float time)
+{
+ simpleCRobot->GetWatchdog().SetExpiration(time);
+}
+
+void WatchdogFeed()
+{
+ simpleCRobot->GetWatchdog().Feed();
+}
+
diff --git a/aos/externals/WPILib/WPILib/CInterfaces/SimpleCRobot.h b/aos/externals/WPILib/WPILib/CInterfaces/SimpleCRobot.h
new file mode 100644
index 0000000..769e760
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CInterfaces/SimpleCRobot.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef SIMPLE_C_ROBOT_H
+#define SIMPLE_C_ROBOT_H
+
+#include "RobotBase.h"
+
+void Autonomous();
+void OperatorControl();
+void Initialize();
+
+bool IsAutonomous();
+bool IsOperatorControl();
+bool IsDisabled();
+
+void SetWatchdogEnabled(bool enable);
+void SetWatchdogExpiration(float time);
+void WatchdogFeed();
+
+class SimpleCRobot: public RobotBase
+{
+public:
+ SimpleCRobot();
+ virtual ~SimpleCRobot() {}
+ void StartCompetition();
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/ChipObject.h b/aos/externals/WPILib/WPILib/ChipObject.h
new file mode 100644
index 0000000..607af92
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __ChipObject_h__
+#define __ChipObject_h__
+
+#include <vxWorks.h>
+#include "ChipObject/NiRio.h"
+
+#include "ChipObject/tAccumulator.h"
+#include "ChipObject/tAI.h"
+#include "ChipObject/tAlarm.h"
+#include "ChipObject/tAnalogTrigger.h"
+#include "ChipObject/tCounter.h"
+#include "ChipObject/tDIO.h"
+#include "ChipObject/tDMA.h"
+//#include "ChipObject/tDMAManager.h"
+#include "ChipObject/tEncoder.h"
+#include "ChipObject/tGlobal.h"
+#include "ChipObject/tInterrupt.h"
+#include "ChipObject/tInterruptManager.h"
+#include "ChipObject/tSolenoid.h"
+#include "ChipObject/tSPI.h"
+#include "ChipObject/tWatchdog.h"
+
+using namespace nFPGA;
+using namespace nFRC_2012_1_6_4;
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/ChipObject/Makefile b/aos/externals/WPILib/WPILib/ChipObject/Makefile
new file mode 100644
index 0000000..bc19164
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/Makefile
@@ -0,0 +1,2184 @@
+# Wind River Workbench generated Makefile.
+# Do not edit!!!
+#
+# The file ".wrmakefile" is the template used by the Wind River Workbench to
+# generate the makefiles of this project. Add user-specific build targets and
+# make rules only(!) in this project's ".wrmakefile" file. These will then be
+# automatically dumped into the makefiles.
+
+WIND_HOME := $(subst \,/,$(WIND_HOME))
+WIND_BASE := $(subst \,/,$(WIND_BASE))
+WIND_USR := $(subst \,/,$(WIND_USR))
+
+all : pre_build main_all post_build
+
+_clean ::
+ @echo "make: removing targets and objects of `pwd`"
+
+TRACE=0
+TRACEON=$(TRACE:0=@)
+TRACE_FLAG=$(TRACEON:1=)
+
+MAKEFILE := Makefile
+
+BUILD_SPEC = PPC603gnu
+DEBUG_MODE = 1
+SRC_DIR := .
+BUILD_ROOT_DIR :=
+PRJ_ROOT_DIR := C:/windriver/workspace/WPILib
+WS_ROOT_DIR := C:/windriver/workspace
+
+ALL_BUILD_SPECS := PPC32diab PPC32gnu PPC32sfdiab PPC32sfgnu \
+ PPC403diab PPC403gnu PPC405diab PPC405gnu \
+ PPC405sfdiab PPC405sfgnu PPC440diab PPC440gnu \
+ PPC440sfdiab PPC440sfgnu PPC603diab PPC603gnu \
+ PPC604diab PPC604gnu PPC85XXdiab PPC85XXgnu \
+ PPC85XXsfdiab PPC85XXsfgnu PPC860sfdiab PPC860sfgnu \
+ SIMLINUXdiab SIMLINUXgnu SIMNTdiab SIMNTgnu \
+ SIMSPARCSOLARISdiab SIMSPARCSOLARISgnu
+ENABLED_BUILD_SPECS := PPC603gnu
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32diab_DEBUG
+else
+OBJ_DIR := PPC32diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32gnu_DEBUG
+else
+OBJ_DIR := PPC32gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfdiab_DEBUG
+else
+OBJ_DIR := PPC32sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfgnu_DEBUG
+else
+OBJ_DIR := PPC32sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403diab_DEBUG
+else
+OBJ_DIR := PPC403diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403gnu_DEBUG
+else
+OBJ_DIR := PPC403gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405diab_DEBUG
+else
+OBJ_DIR := PPC405diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405gnu_DEBUG
+else
+OBJ_DIR := PPC405gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfdiab_DEBUG
+else
+OBJ_DIR := PPC405sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfgnu_DEBUG
+else
+OBJ_DIR := PPC405sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440diab_DEBUG
+else
+OBJ_DIR := PPC440diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440gnu_DEBUG
+else
+OBJ_DIR := PPC440gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfdiab_DEBUG
+else
+OBJ_DIR := PPC440sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfgnu_DEBUG
+else
+OBJ_DIR := PPC440sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603diab_DEBUG
+else
+OBJ_DIR := PPC603diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603gnu_DEBUG
+else
+OBJ_DIR := PPC603gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604diab_DEBUG
+else
+OBJ_DIR := PPC604diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604gnu_DEBUG
+else
+OBJ_DIR := PPC604gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXdiab_DEBUG
+else
+OBJ_DIR := PPC85XXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXgnu_DEBUG
+else
+OBJ_DIR := PPC85XXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfdiab_DEBUG
+else
+OBJ_DIR := PPC85XXsfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfgnu_DEBUG
+else
+OBJ_DIR := PPC85XXsfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfdiab_DEBUG
+else
+OBJ_DIR := PPC860sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfgnu_DEBUG
+else
+OBJ_DIR := PPC860sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXdiab_DEBUG
+else
+OBJ_DIR := SIMLINUXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXgnu_DEBUG
+else
+OBJ_DIR := SIMLINUXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTdiab_DEBUG
+else
+OBJ_DIR := SIMNTdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTgnu_DEBUG
+else
+OBJ_DIR := SIMNTgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISdiab_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISgnu_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISgnu
+endif
+endif
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+
+PROJECT_TYPE = DKM
+DEFINES =
+EXPAND_DBG = 0
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFH:vxworks63 -Xstmw-slow -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mhard-float -mstrict-align -mno-implicit-fp -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -msoft-float -mstrict-align
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC403FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=403 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC603FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=603 -mstrict-align -mno-implicit-fp -mlongcall
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I.. -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC604FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=604 -mstrict-align -mno-implicit-fp
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC860FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=860 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tSPARCFH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC =
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+
+
+
+
+
+-include $(PRJ_ROOT_DIR)/*.makefile
+
+-include *.makefile
+
+main_all : external_build $(PROJECT_TARGETS)
+ @echo "make: built targets of `pwd`"
+
+# entry point for extending the build
+external_build ::
+ @echo ""
+
+# main entry point for pre processing prior to the build
+pre_build :: $(PRE_BUILD_STEP) generate_sources
+ @echo ""
+
+# entry point for generating sources prior to the build
+generate_sources ::
+ @echo ""
+
+# main entry point for post processing after the build
+post_build :: $(POST_BUILD_STEP) deploy_output
+ @echo ""
+
+# entry point for deploying output after the build
+deploy_output ::
+ @echo ""
+
+clean :: external_clean $(CLEAN_STEP) _clean
+
+# entry point for extending the build clean
+external_clean ::
+ @echo ""
diff --git a/aos/externals/WPILib/WPILib/ChipObject/NiFpga.h b/aos/externals/WPILib/WPILib/ChipObject/NiFpga.h
new file mode 100644
index 0000000..c5f2bce
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/NiFpga.h
@@ -0,0 +1,2311 @@
+/*
+ * FPGA Interface C API 2.0 header file.
+ *
+ * Copyright (c) 2011,
+ * National Instruments Corporation.
+ * All rights reserved.
+ */
+
+#ifndef __NiFpga_h__
+#define __NiFpga_h__
+
+/*
+ * Determine platform details.
+ */
+#if defined(_M_IX86) \
+ || defined(_M_X64) \
+ || defined(i386) \
+ || defined(__i386__) \
+ || defined(__amd64__) \
+ || defined(__amd64) \
+ || defined(__x86_64__) \
+ || defined(__x86_64) \
+ || defined(__i386) \
+ || defined(_X86_) \
+ || defined(__THW_INTEL__) \
+ || defined(__I86__) \
+ || defined(__INTEL__) \
+ || defined(__X86__) \
+ || defined(__386__) \
+ || defined(__I86__) \
+ || defined(M_I386) \
+ || defined(M_I86) \
+ || defined(_M_I386) \
+ || defined(_M_I86)
+ #if defined(_WIN32) \
+ || defined(_WIN64) \
+ || defined(__WIN32__) \
+ || defined(__TOS_WIN__) \
+ || defined(__WINDOWS__) \
+ || defined(_WINDOWS) \
+ || defined(__WINDOWS_386__) \
+ || defined(__CYGWIN__)
+ /* Either Windows or Phar Lap ETS. */
+ #define NiFpga_Windows 1
+ #elif defined(__linux) \
+ || defined(__linux__) \
+ || defined(__gnu_linux__) \
+ || defined(linux)
+ #define NiFpga_Linux 1
+ #else
+ #error Unsupported OS.
+ #endif
+#elif defined(__powerpc) \
+ || defined(__powerpc__) \
+ || defined(__POWERPC__) \
+ || defined(__ppc__) \
+ || defined(__PPC) \
+ || defined(_M_PPC) \
+ || defined(_ARCH_PPC) \
+ || defined(__PPC__) \
+ || defined(__ppc)
+ #if defined(__vxworks)
+ #define NiFpga_VxWorks 1
+ #else
+ #error Unsupported OS.
+ #endif
+#else
+ #error Unsupported architecture.
+#endif
+
+/*
+ * Determine compiler.
+ */
+#if defined(_MSC_VER)
+ #define NiFpga_Msvc 1
+#elif defined(__GNUC__)
+ #define NiFpga_Gcc 1
+#elif defined(_CVI_) && !defined(_TPC_)
+ #define NiFpga_Cvi 1
+ /* Enables CVI Library Protection Errors. */
+ #pragma EnableLibraryRuntimeChecking
+#else
+ /* Unknown compiler. */
+#endif
+
+/*
+ * Determine compliance with different C/C++ language standards.
+ */
+#if defined(__cplusplus)
+ #define NiFpga_Cpp 1
+ #if __cplusplus >= 199707L
+ #define NiFpga_Cpp98 1
+ #endif
+#endif
+#if defined(__STDC__)
+ #define NiFpga_C89 1
+ #if defined(__STDC_VERSION__)
+ #define NiFpga_C90 1
+ #if __STDC_VERSION__ >= 199409L
+ #define NiFpga_C94 1
+ #if __STDC_VERSION__ >= 199901L
+ #define NiFpga_C99 1
+ #endif
+ #endif
+ #endif
+#endif
+
+/*
+ * Determine ability to inline functions.
+ */
+#if NiFpga_Cpp || NiFpga_C99
+ /* The inline keyword exists in C++ and C99. */
+ #define NiFpga_Inline inline
+#elif NiFpga_Msvc
+ /* Visual C++ (at least since 6.0) also supports an alternate keyword. */
+ #define NiFpga_Inline __inline
+#elif NiFpga_Gcc
+ /* GCC (at least since 2.95.2) also supports an alternate keyword. */
+ #define NiFpga_Inline __inline__
+#elif !defined(NiFpga_Inline)
+ /*
+ * Disable inlining if inline support is unknown. To manually enable
+ * inlining, #define the following macro before #including NiFpga.h:
+ *
+ * #define NiFpga_Inline inline
+ */
+ #define NiFpga_Inline
+#endif
+
+/*
+ * Define exact-width integer types, if they have not already been defined.
+ */
+#if NiFpga_ExactWidthIntegerTypesDefined \
+ || defined(_STDINT) \
+ || defined(_STDINT_H) \
+ || defined(_STDINT_H_) \
+ || defined(_INTTYPES_H) \
+ || defined(_INTTYPES_H_) \
+ || defined(_SYS_STDINT_H) \
+ || defined(_SYS_STDINT_H_) \
+ || defined(_SYS_INTTYPES_H) \
+ || defined(_SYS_INTTYPES_H_) \
+ || defined(_STDINT_H_INCLUDED) \
+ || defined(BOOST_CSTDINT_HPP) \
+ || defined(_MSC_STDINT_H_) \
+ || defined(_PSTDINT_H_INCLUDED)
+ /* Assume that exact-width integer types have already been defined. */
+#elif NiFpga_VxWorks
+ #include <vxWorks.h>
+#elif NiFpga_C99 \
+ || NiFpga_Gcc /* GCC (at least since 3.0) has a stdint.h. */ \
+ || defined(HAVE_STDINT_H)
+ /* Assume that stdint.h can be included. */
+ #include <stdint.h>
+#elif NiFpga_Msvc \
+ || NiFpga_Cvi
+ /* Manually define exact-width integer types. */
+ typedef signed char int8_t;
+ typedef unsigned char uint8_t;
+ typedef short int16_t;
+ typedef unsigned short uint16_t;
+ typedef int int32_t;
+ typedef unsigned int uint32_t;
+ typedef __int64 int64_t;
+ typedef unsigned __int64 uint64_t;
+#else
+ /*
+ * Exact-width integer types must be defined by the user, and the following
+ * macro must be #defined, before #including NiFpga.h:
+ *
+ * #define NiFpga_ExactWidthIntegerTypesDefined 1
+ */
+ #error Exact-width integer types must be defined by the user. See comment.
+#endif
+
+/* Included for definition of size_t. */
+#include <stddef.h>
+
+#if NiFpga_Cpp
+extern "C" {
+#endif
+
+/**
+ * A boolean value; either NiFpga_False or NiFpga_True.
+ */
+typedef uint8_t NiFpga_Bool;
+
+/**
+ * Represents a false condition.
+ */
+static const NiFpga_Bool NiFpga_False = 0;
+
+/**
+ * Represents a true condition.
+ */
+static const NiFpga_Bool NiFpga_True = 1;
+
+/**
+ * Represents the resulting status of a function call through its return value.
+ * 0 is success, negative values are errors, and positive values are warnings.
+ */
+typedef int32_t NiFpga_Status;
+
+/**
+ * No errors or warnings.
+ */
+static const NiFpga_Status NiFpga_Status_Success = 0;
+
+/**
+ * The timeout expired before the FIFO operation could complete.
+ */
+static const NiFpga_Status NiFpga_Status_FifoTimeout = -50400;
+
+/**
+ * A memory allocation failed. Try again after rebooting.
+ */
+static const NiFpga_Status NiFpga_Status_MemoryFull = -52000;
+
+/**
+ * An unexpected software error occurred.
+ */
+static const NiFpga_Status NiFpga_Status_SoftwareFault = -52003;
+
+/**
+ * A parameter to a function was not valid. This could be a NULL pointer, a bad
+ * value, etc.
+ */
+static const NiFpga_Status NiFpga_Status_InvalidParameter = -52005;
+
+/**
+ * A required resource was not found. The NiFpga.* library, the RIO resource,
+ * or some other resource may be missing, or the NiFpga.* library may not be
+ * the required minimum version.
+ */
+static const NiFpga_Status NiFpga_Status_ResourceNotFound = -52006;
+
+/**
+ * A required resource was not properly initialized. This could occur if
+ * NiFpga_Initialize was not called or a required NiFpga_IrqContext was not
+ * reserved.
+ */
+static const NiFpga_Status NiFpga_Status_ResourceNotInitialized = -52010;
+
+/**
+ * The FPGA is already running.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaAlreadyRunning = -61003;
+
+/**
+ * The bitfile was not compiled for the specified resource's device type.
+ */
+static const NiFpga_Status NiFpga_Status_DeviceTypeMismatch = -61024;
+
+/**
+ * An error was detected in the communication between the host computer and the
+ * FPGA target.
+ */
+static const NiFpga_Status NiFpga_Status_CommunicationTimeout = -61046;
+
+/**
+ * The timeout expired before any of the IRQs were asserted.
+ */
+static const NiFpga_Status NiFpga_Status_IrqTimeout = -61060;
+
+/**
+ * The specified bitfile is invalid or corrupt.
+ */
+static const NiFpga_Status NiFpga_Status_CorruptBitfile = -61070;
+
+/**
+ * The FIFO depth is invalid. It was either 0, greater than the amount of
+ * available memory in the host computer, or greater than the maximum size
+ * allowed by the hardware.
+ */
+static const NiFpga_Status NiFpga_Status_BadDepth = -61072;
+
+/**
+ * The number of FIFO elements is invalid. Either the number is greater than
+ * the depth of the host memory DMA FIFO, or more elements were requested for
+ * release than had been acquired.
+ */
+static const NiFpga_Status NiFpga_Status_BadReadWriteCount = -61073;
+
+/**
+ * A hardware clocking error occurred. A derived clock lost lock with its base
+ * clock during the execution of the LabVIEW FPGA VI. If any base clocks with
+ * derived clocks are referencing an external source, make sure that the
+ * external source is connected and within the supported frequency, jitter,
+ * accuracy, duty cycle, and voltage specifications. Also verify that the
+ * characteristics of the base clock match the configuration specified in the
+ * FPGA Base Clock Properties. If all base clocks with derived clocks are
+ * generated from free-running, on-board sources, please contact National
+ * Instruments technical support at ni.com/support.
+ */
+static const NiFpga_Status NiFpga_Status_ClockLostLock = -61083;
+
+/**
+ * Operation could not be performed because the FPGA is busy. Stop all the
+ * activities on the FPGA before requesting this operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusy = -61141;
+
+/**
+ * Operation could not be performed because the FPGA is busy operating in FPGA
+ * Interface C API mode. Stop all the activities on the FPGA before requesting
+ * this operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyFpgaInterfaceCApi = -61200;
+
+/**
+ * The chassis is in Scan Interface programming mode. In order to run FPGA VIs,
+ * you must go to the chassis properties page, select FPGA programming mode,
+ * and deploy settings.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyScanInterface = -61201;
+
+/**
+ * Operation could not be performed because the FPGA is busy operating in FPGA
+ * Interface mode. Stop all the activities on the FPGA before requesting this
+ * operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyFpgaInterface = -61202;
+
+/**
+ * Operation could not be performed because the FPGA is busy operating in
+ * Interactive mode. Stop all the activities on the FPGA before requesting this
+ * operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyInteractive = -61203;
+
+/**
+ * Operation could not be performed because the FPGA is busy operating in
+ * Emulation mode. Stop all the activities on the FPGA before requesting this
+ * operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyEmulation = -61204;
+
+/**
+ * An unexpected internal error occurred.
+ */
+static const NiFpga_Status NiFpga_Status_InternalError = -61499;
+
+/**
+ * Access to the remote system was denied. Use MAX to check the Remote Device
+ * Access settings under Software>>NI-RIO>>NI-RIO Settings on the remote system.
+ */
+static const NiFpga_Status NiFpga_Status_AccessDenied = -63033;
+
+/**
+ * A connection could not be established to the specified remote device. Ensure
+ * that the device is on and accessible over the network, that NI-RIO software
+ * is installed, and that the RIO server is running and properly configured.
+ */
+static const NiFpga_Status NiFpga_Status_RpcConnectionError = -63040;
+
+/**
+ * The RPC session is invalid. The target may have reset or been rebooted. Check
+ * the network connection and retry the operation.
+ */
+static const NiFpga_Status NiFpga_Status_RpcSessionError = -63043;
+
+/**
+ * A Read FIFO or Write FIFO function was called while the host had acquired
+ * elements of the FIFO. Release all acquired elements before reading or
+ * writing.
+ */
+static const NiFpga_Status NiFpga_Status_FifoElementsCurrentlyAcquired = -63083;
+
+/**
+ * The bitfile could not be read.
+ */
+static const NiFpga_Status NiFpga_Status_BitfileReadError = -63101;
+
+/**
+ * The specified signature does not match the signature of the bitfile. If the
+ * bitfile has been recompiled, regenerate the C API and rebuild the
+ * application.
+ */
+static const NiFpga_Status NiFpga_Status_SignatureMismatch = -63106;
+
+/**
+ * Either the supplied resource name is invalid as a RIO resource name, or the
+ * device was not found. Use MAX to find the proper resource name for the
+ * intended device.
+ */
+static const NiFpga_Status NiFpga_Status_InvalidResourceName = -63192;
+
+/**
+ * The requested feature is not supported.
+ */
+static const NiFpga_Status NiFpga_Status_FeatureNotSupported = -63193;
+
+/**
+ * The NI-RIO software on the remote system is not compatible with the local
+ * NI-RIO software. Upgrade the NI-RIO software on the remote system.
+ */
+static const NiFpga_Status NiFpga_Status_VersionMismatch = -63194;
+
+/**
+ * The session is invalid or has been closed.
+ */
+static const NiFpga_Status NiFpga_Status_InvalidSession = -63195;
+
+/**
+ * The maximum number of open FPGA sessions has been reached. Close some open
+ * sessions.
+ */
+static const NiFpga_Status NiFpga_Status_OutOfHandles = -63198;
+
+/**
+ * Tests whether a status is an error.
+ *
+ * @param status status to check for an error
+ * @return whether the status was an error
+ */
+static NiFpga_Inline NiFpga_Bool NiFpga_IsError(const NiFpga_Status status)
+{
+ return status < NiFpga_Status_Success;
+}
+
+/**
+ * Tests whether a status is not an error. Success and warnings are not errors.
+ *
+ * @param status status to check for an error
+ * @return whether the status was a success or warning
+ */
+static NiFpga_Inline NiFpga_Bool NiFpga_IsNotError(const NiFpga_Status status)
+{
+ return status >= NiFpga_Status_Success;
+}
+
+/**
+ * Conditionally sets the status to a new value. The previous status is
+ * preserved unless the new status is more of an error, which means that
+ * warnings and errors overwrite successes, and errors overwrite warnings. New
+ * errors do not overwrite older errors, and new warnings do not overwrite
+ * older warnings.
+ *
+ * @param status status to conditionally set
+ * @param newStatus new status value that may be set
+ * @return the resulting status
+ */
+static NiFpga_Inline NiFpga_Status NiFpga_MergeStatus(
+ NiFpga_Status* const status,
+ const NiFpga_Status newStatus)
+{
+ if (!status)
+ {
+ return NiFpga_Status_InvalidParameter;
+ }
+ if (NiFpga_IsNotError(*status)
+ && (*status == NiFpga_Status_Success || NiFpga_IsError(newStatus)))
+ {
+ *status = newStatus;
+ }
+ return *status;
+}
+
+/**
+ * This macro evaluates the expression only if the status is not an error. The
+ * expression must evaluate to an NiFpga_Status, such as a call to any NiFpga_*
+ * function, because the status will be set to the returned status if the
+ * expression is evaluated.
+ *
+ * You can use this macro to mimic status chaining in LabVIEW, where the status
+ * does not have to be explicitly checked after each call. Such code may look
+ * like the following example.
+ *
+ * NiFpga_Status status = NiFpga_Status_Success;
+ * NiFpga_IfIsNotError(status, NiFpga_WriteU32(...));
+ * NiFpga_IfIsNotError(status, NiFpga_WriteU32(...));
+ * NiFpga_IfIsNotError(status, NiFpga_WriteU32(...));
+ *
+ * @param status status to check for an error
+ * @param expression expression to call if the incoming status is not an error
+ */
+#define NiFpga_IfIsNotError(status, expression) \
+ if (NiFpga_IsNotError(status)) \
+ { \
+ NiFpga_MergeStatus(&status, (expression)); \
+ }
+
+/**
+ * You must call this function before all other function calls. This function
+ * loads the NiFpga library so that all the other functions will work. If this
+ * function succeeds, you must call NiFpga_Finalize after all other function
+ * calls.
+ *
+ * @warning This function is not thread safe.
+ *
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Initialize(void);
+
+/**
+ * You must call this function after all other function calls if
+ * NiFpga_Initialize succeeds. This function unloads the NiFpga library.
+ *
+ * @warning This function is not thread safe.
+ *
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Finalize(void);
+
+/**
+ * A handle to an FPGA session.
+ */
+typedef uint32_t NiFpga_Session;
+
+/**
+ * Attributes that NiFpga_Open accepts.
+ */
+typedef enum
+{
+ NiFpga_OpenAttribute_NoRun = 1
+} NiFpga_OpenAttribute;
+
+/**
+ * Opens a session to the FPGA. This call ensures that the contents of the
+ * bitfile are programmed to the FPGA. The FPGA runs unless the
+ * NiFpga_OpenAttribute_NoRun attribute is used.
+ *
+ * Because different operating systems have different default current working
+ * directories for applications, you must pass an absolute path for the bitfile
+ * parameter. If you pass only the filename instead of an absolute path, the
+ * operating system may not be able to locate the bitfile. For example, the
+ * default current working directories are C:\ni-rt\system\ for Phar Lap ETS and
+ * /c/ for VxWorks. Because the generated *_Bitfile constant is a #define to a
+ * string literal, you can use C/C++ string-literal concatenation to form an
+ * absolute path. For example, if the bitfile is in the root directory of a
+ * Phar Lap ETS system, pass the following for the bitfile parameter.
+ *
+ * "C:\\" NiFpga_MyApplication_Bitfile
+ *
+ * @param bitfile path to the bitfile
+ * @param signature signature of the bitfile
+ * @param resource RIO resource string to open ("RIO0" or "rio://mysystem/RIO")
+ * @param attribute bitwise OR of any NiFpga_OpenAttributes, or 0
+ * @param session outputs the session handle, which must be closed when no
+ * longer needed
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Open(const char* bitfile,
+ const char* signature,
+ const char* resource,
+ uint32_t attribute,
+ NiFpga_Session* session);
+
+/**
+ * Attributes that NiFpga_Close accepts.
+ */
+typedef enum
+{
+ NiFpga_CloseAttribute_NoResetIfLastSession = 1
+} NiFpga_CloseAttribute;
+
+/**
+ * Closes the session to the FPGA. The FPGA resets unless either another session
+ * is still open or you use the NiFpga_CloseAttribute_NoResetIfLastSession
+ * attribute.
+ *
+ * @param session handle to a currently open session
+ * @param attribute bitwise OR of any NiFpga_CloseAttributes, or 0
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Close(NiFpga_Session session,
+ uint32_t attribute);
+
+/**
+ * Attributes that NiFpga_Run accepts.
+ */
+typedef enum
+{
+ NiFpga_RunAttribute_WaitUntilDone = 1
+} NiFpga_RunAttribute;
+
+/**
+ * Runs the FPGA VI on the target. If you use NiFpga_RunAttribute_WaitUntilDone,
+ * NiFpga_Run blocks the thread until the FPGA finishes running (if ever).
+ *
+ * @param session handle to a currently open session
+ * @param attribute bitwise OR of any NiFpga_RunAttributes, or 0
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Run(NiFpga_Session session,
+ uint32_t attribute);
+
+/**
+ * Aborts the FPGA VI.
+ *
+ * @param session handle to a currently open session
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Abort(NiFpga_Session session);
+
+/**
+ * Resets the FPGA VI.
+ *
+ * @param session handle to a currently open session
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Reset(NiFpga_Session session);
+
+/**
+ * Re-downloads the FPGA bitstream to the target.
+ *
+ * @param session handle to a currently open session
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Download(NiFpga_Session session);
+
+/**
+ * Reads a boolean value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadBool(NiFpga_Session session,
+ uint32_t indicator,
+ NiFpga_Bool* value);
+
+/**
+ * Reads a signed 8-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadI8(NiFpga_Session session,
+ uint32_t indicator,
+ int8_t* value);
+
+/**
+ * Reads an unsigned 8-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadU8(NiFpga_Session session,
+ uint32_t indicator,
+ uint8_t* value);
+
+/**
+ * Reads a signed 16-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadI16(NiFpga_Session session,
+ uint32_t indicator,
+ int16_t* value);
+
+/**
+ * Reads an unsigned 16-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadU16(NiFpga_Session session,
+ uint32_t indicator,
+ uint16_t* value);
+
+/**
+ * Reads a signed 32-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadI32(NiFpga_Session session,
+ uint32_t indicator,
+ int32_t* value);
+
+/**
+ * Reads an unsigned 32-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadU32(NiFpga_Session session,
+ uint32_t indicator,
+ uint32_t* value);
+
+/**
+ * Reads a signed 64-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadI64(NiFpga_Session session,
+ uint32_t indicator,
+ int64_t* value);
+
+/**
+ * Reads an unsigned 64-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadU64(NiFpga_Session session,
+ uint32_t indicator,
+ uint64_t* value);
+
+/**
+ * Writes a boolean value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteBool(NiFpga_Session session,
+ uint32_t control,
+ NiFpga_Bool value);
+
+/**
+ * Writes a signed 8-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteI8(NiFpga_Session session,
+ uint32_t control,
+ int8_t value);
+
+/**
+ * Writes an unsigned 8-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteU8(NiFpga_Session session,
+ uint32_t control,
+ uint8_t value);
+
+/**
+ * Writes a signed 16-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteI16(NiFpga_Session session,
+ uint32_t control,
+ int16_t value);
+
+/**
+ * Writes an unsigned 16-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteU16(NiFpga_Session session,
+ uint32_t control,
+ uint16_t value);
+
+/**
+ * Writes a signed 32-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteI32(NiFpga_Session session,
+ uint32_t control,
+ int32_t value);
+
+/**
+ * Writes an unsigned 32-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteU32(NiFpga_Session session,
+ uint32_t control,
+ uint32_t value);
+
+/**
+ * Writes a signed 64-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteI64(NiFpga_Session session,
+ uint32_t control,
+ int64_t value);
+
+/**
+ * Writes an unsigned 64-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteU64(NiFpga_Session session,
+ uint32_t control,
+ uint64_t value);
+
+/**
+ * Reads an entire array of boolean values from a given array indicator or
+ * control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayBool(NiFpga_Session session,
+ uint32_t indicator,
+ NiFpga_Bool* array,
+ size_t size);
+
+/**
+ * Reads an entire array of signed 8-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayI8(NiFpga_Session session,
+ uint32_t indicator,
+ int8_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of unsigned 8-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayU8(NiFpga_Session session,
+ uint32_t indicator,
+ uint8_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of signed 16-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayI16(NiFpga_Session session,
+ uint32_t indicator,
+ int16_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of unsigned 16-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayU16(NiFpga_Session session,
+ uint32_t indicator,
+ uint16_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of signed 32-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayI32(NiFpga_Session session,
+ uint32_t indicator,
+ int32_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of unsigned 32-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayU32(NiFpga_Session session,
+ uint32_t indicator,
+ uint32_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of signed 64-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayI64(NiFpga_Session session,
+ uint32_t indicator,
+ int64_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of unsigned 64-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayU64(NiFpga_Session session,
+ uint32_t indicator,
+ uint64_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of boolean values to a given array control or
+ * indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayBool(NiFpga_Session session,
+ uint32_t control,
+ const NiFpga_Bool* array,
+ size_t size);
+
+/**
+ * Writes an entire array of signed 8-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayI8(NiFpga_Session session,
+ uint32_t control,
+ const int8_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of unsigned 8-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayU8(NiFpga_Session session,
+ uint32_t control,
+ const uint8_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of signed 16-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayI16(NiFpga_Session session,
+ uint32_t control,
+ const int16_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of unsigned 16-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayU16(NiFpga_Session session,
+ uint32_t control,
+ const uint16_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of signed 32-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayI32(NiFpga_Session session,
+ uint32_t control,
+ const int32_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of unsigned 32-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayU32(NiFpga_Session session,
+ uint32_t control,
+ const uint32_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of signed 64-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayI64(NiFpga_Session session,
+ uint32_t control,
+ const int64_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of unsigned 64-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayU64(NiFpga_Session session,
+ uint32_t control,
+ const uint64_t* array,
+ size_t size);
+
+/**
+ * Enumeration of all 32 possible IRQs. Multiple IRQs can be bitwise ORed
+ * together like this:
+ *
+ * NiFpga_Irq_3 | NiFpga_Irq_23
+ */
+typedef enum
+{
+ NiFpga_Irq_0 = 1 << 0,
+ NiFpga_Irq_1 = 1 << 1,
+ NiFpga_Irq_2 = 1 << 2,
+ NiFpga_Irq_3 = 1 << 3,
+ NiFpga_Irq_4 = 1 << 4,
+ NiFpga_Irq_5 = 1 << 5,
+ NiFpga_Irq_6 = 1 << 6,
+ NiFpga_Irq_7 = 1 << 7,
+ NiFpga_Irq_8 = 1 << 8,
+ NiFpga_Irq_9 = 1 << 9,
+ NiFpga_Irq_10 = 1 << 10,
+ NiFpga_Irq_11 = 1 << 11,
+ NiFpga_Irq_12 = 1 << 12,
+ NiFpga_Irq_13 = 1 << 13,
+ NiFpga_Irq_14 = 1 << 14,
+ NiFpga_Irq_15 = 1 << 15,
+ NiFpga_Irq_16 = 1 << 16,
+ NiFpga_Irq_17 = 1 << 17,
+ NiFpga_Irq_18 = 1 << 18,
+ NiFpga_Irq_19 = 1 << 19,
+ NiFpga_Irq_20 = 1 << 20,
+ NiFpga_Irq_21 = 1 << 21,
+ NiFpga_Irq_22 = 1 << 22,
+ NiFpga_Irq_23 = 1 << 23,
+ NiFpga_Irq_24 = 1 << 24,
+ NiFpga_Irq_25 = 1 << 25,
+ NiFpga_Irq_26 = 1 << 26,
+ NiFpga_Irq_27 = 1 << 27,
+ NiFpga_Irq_28 = 1 << 28,
+ NiFpga_Irq_29 = 1 << 29,
+ NiFpga_Irq_30 = 1 << 30,
+ NiFpga_Irq_31 = 1U << 31
+} NiFpga_Irq;
+
+/**
+ * Represents an infinite timeout.
+ */
+static const uint32_t NiFpga_InfiniteTimeout = 0xFFFFFFFF;
+
+/**
+ * See NiFpga_ReserveIrqContext for more information.
+ */
+typedef void* NiFpga_IrqContext;
+
+/**
+ * IRQ contexts are single-threaded; only one thread can wait with a particular
+ * context at any given time. Clients must reserve as many contexts as the
+ * application requires.
+ *
+ * If a context is successfully reserved (the returned status is not an error),
+ * it must be unreserved later. Otherwise a memory leak will occur.
+ *
+ * @param session handle to a currently open session
+ * @param context outputs the IRQ context
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReserveIrqContext(NiFpga_Session session,
+ NiFpga_IrqContext* context);
+
+/**
+ * Unreserves an IRQ context obtained from NiFpga_ReserveIrqContext.
+ *
+ * @param session handle to a currently open session
+ * @param context IRQ context to unreserve
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_UnreserveIrqContext(NiFpga_Session session,
+ NiFpga_IrqContext context);
+
+/**
+ * This is a blocking function that stops the calling thread until the FPGA
+ * asserts any IRQ in the irqs parameter, or until the function call times out.
+ * Before calling this function, you must use NiFpga_ReserveIrqContext to
+ * reserve an IRQ context. No other threads can use the same context when this
+ * function is called.
+ *
+ * You can use the irqsAsserted parameter to determine which IRQs were asserted
+ * for each function call.
+ *
+ * @param session handle to a currently open session
+ * @param context IRQ context with which to wait
+ * @param irqs bitwise OR of NiFpga_Irqs
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param irqsAsserted if non-NULL, outputs bitwise OR of IRQs that were
+ * asserted
+ * @param timedOut if non-NULL, outputs whether the timeout expired
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WaitOnIrqs(NiFpga_Session session,
+ NiFpga_IrqContext context,
+ uint32_t irqs,
+ uint32_t timeout,
+ uint32_t* irqsAsserted,
+ NiFpga_Bool* timedOut);
+
+/**
+ * Acknowledges an IRQ or set of IRQs.
+ *
+ * @param session handle to a currently open session
+ * @param irqs bitwise OR of NiFpga_Irqs
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcknowledgeIrqs(NiFpga_Session session,
+ uint32_t irqs);
+
+/**
+ * Specifies the depth of the host memory part of the DMA FIFO. This method is
+ * optional. In order to see the actual depth configured, use
+ * NiFpga_ConfigureFifo2.
+ *
+ * @param session handle to a currently open session
+ * @param fifo FIFO to configure
+ * @param depth requested number of elements in the host memory part of the
+ * DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ConfigureFifo(NiFpga_Session session,
+ uint32_t fifo,
+ size_t depth);
+
+/**
+ * Specifies the depth of the host memory part of the DMA FIFO. This method is
+ * optional.
+ *
+ * @param session handle to a currently open session
+ * @param fifo FIFO to configure
+ * @param requestedDepth requested number of elements in the host memory part
+ * of the DMA FIFO
+ * @param actualDepth if non-NULL, outputs the actual number of elements in the
+ * host memory part of the DMA FIFO, which may be more than
+ * the requested number
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ConfigureFifo2(NiFpga_Session session,
+ uint32_t fifo,
+ size_t requestedDepth,
+ size_t* actualDepth);
+/**
+ * Starts a FIFO. This method is optional.
+ *
+ * @param session handle to a currently open session
+ * @param fifo FIFO to start
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_StartFifo(NiFpga_Session session,
+ uint32_t fifo);
+
+/**
+ * Stops a FIFO. This method is optional.
+ *
+ * @param session handle to a currently open session
+ * @param fifo FIFO to stop
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_StopFifo(NiFpga_Session session,
+ uint32_t fifo);
+
+/**
+ * Reads from a target-to-host FIFO of booleans.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoBool(NiFpga_Session session,
+ uint32_t fifo,
+ NiFpga_Bool* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of signed 8-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoI8(NiFpga_Session session,
+ uint32_t fifo,
+ int8_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of unsigned 8-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoU8(NiFpga_Session session,
+ uint32_t fifo,
+ uint8_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of signed 16-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoI16(NiFpga_Session session,
+ uint32_t fifo,
+ int16_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of unsigned 16-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoU16(NiFpga_Session session,
+ uint32_t fifo,
+ uint16_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of signed 32-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoI32(NiFpga_Session session,
+ uint32_t fifo,
+ int32_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of unsigned 32-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoU32(NiFpga_Session session,
+ uint32_t fifo,
+ uint32_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of signed 64-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoI64(NiFpga_Session session,
+ uint32_t fifo,
+ int64_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of unsigned 64-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoU64(NiFpga_Session session,
+ uint32_t fifo,
+ uint64_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of booleans.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoBool(NiFpga_Session session,
+ uint32_t fifo,
+ const NiFpga_Bool* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of signed 8-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoI8(NiFpga_Session session,
+ uint32_t fifo,
+ const int8_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of unsigned 8-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoU8(NiFpga_Session session,
+ uint32_t fifo,
+ const uint8_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of signed 16-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoI16(NiFpga_Session session,
+ uint32_t fifo,
+ const int16_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of unsigned 16-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoU16(NiFpga_Session session,
+ uint32_t fifo,
+ const uint16_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of signed 32-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoI32(NiFpga_Session session,
+ uint32_t fifo,
+ const int32_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of unsigned 32-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoU32(NiFpga_Session session,
+ uint32_t fifo,
+ const uint32_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of signed 64-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoI64(NiFpga_Session session,
+ uint32_t fifo,
+ const int64_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of unsigned 64-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoU64(NiFpga_Session session,
+ uint32_t fifo,
+ const uint64_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of booleans.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsBool(
+ NiFpga_Session session,
+ uint32_t fifo,
+ NiFpga_Bool** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of signed 8-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsI8(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int8_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of unsigned 8-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsU8(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint8_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of signed 16-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsI16(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int16_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of unsigned 16-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsU16(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint16_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of signed 32-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsI32(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int32_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of unsigned 32-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsU32(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint32_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of signed 64-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsI64(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int64_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of unsigned 64-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsU64(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint64_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of booleans.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsBool(
+ NiFpga_Session session,
+ uint32_t fifo,
+ NiFpga_Bool** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of signed 8-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsI8(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int8_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of unsigned 8-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsU8(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint8_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of signed 16-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsI16(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int16_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of unsigned 16-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsU16(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint16_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of signed 32-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsI32(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int32_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of unsigned 32-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsU32(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint32_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of signed 64-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsI64(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int64_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of unsigned 64-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested reqested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsU64(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint64_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Releases previously acquired FIFO elements.
+ *
+ * The FPGA target cannot read elements acquired by the host. Therefore, the
+ * host must release elements after acquiring them. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo FIFO from which to release elements
+ * @param elements number of elements to release
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReleaseFifoElements(NiFpga_Session session,
+ uint32_t fifo,
+ size_t elements);
+
+/**
+ * Gets an endpoint reference to a peer-to-peer FIFO.
+ *
+ * @param session handle to a currently open session
+ * @param fifo peer-to-peer FIFO
+ * @param endpoint outputs the endpoint reference
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_GetPeerToPeerFifoEndpoint(NiFpga_Session session,
+ uint32_t fifo,
+ uint32_t* endpoint);
+
+#if NiFpga_Cpp
+}
+#endif
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/ChipObject/NiRio.h b/aos/externals/WPILib/WPILib/ChipObject/NiRio.h
new file mode 100644
index 0000000..c0dc29e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/NiRio.h
@@ -0,0 +1,9 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+
+#ifndef __NiRio_h__
+#define __NiRio_h__
+
+#include "NiFpga.h"
+typedef NiFpga_Status tRioStatusCode;
+
+#endif // __NiRio_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tAI.h b/aos/externals/WPILib/WPILib/ChipObject/tAI.h
new file mode 100644
index 0000000..38b3f8e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tAI.h
@@ -0,0 +1,138 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_AI_h__
+#define __nFRC_2012_1_6_4_AI_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tAI
+{
+public:
+ tAI(){}
+ virtual ~tAI(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAI* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 2,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ unsigned Channel : 3;
+ unsigned Module : 1;
+ unsigned Averaged : 1;
+ };
+ struct{
+ unsigned value : 5;
+ };
+ } tReadSelect;
+ typedef
+ union{
+ struct{
+ unsigned ScanSize : 3;
+ unsigned ConvertRate : 26;
+ };
+ struct{
+ unsigned value : 29;
+ };
+ } tConfig;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ScanSize(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ConvertRate(unsigned int value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_ScanSize(tRioStatusCode *status) = 0;
+ virtual unsigned int readConfig_ConvertRate(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumScanListElements = 8,
+ } tScanList_IfaceConstants;
+
+ virtual void writeScanList(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readScanList(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLoopTiming_IfaceConstants;
+
+ virtual unsigned int readLoopTiming(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumAverageBitsElements = 8,
+ } tAverageBits_IfaceConstants;
+
+ virtual void writeAverageBits(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readAverageBits(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumOversampleBitsElements = 8,
+ } tOversampleBits_IfaceConstants;
+
+ virtual void writeOversampleBits(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readOversampleBits(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual signed int readOutput(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReadSelect_IfaceConstants;
+
+ virtual void writeReadSelect(tReadSelect value, tRioStatusCode *status) = 0;
+ virtual void writeReadSelect_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeReadSelect_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeReadSelect_Averaged(bool value, tRioStatusCode *status) = 0;
+ virtual tReadSelect readReadSelect(tRioStatusCode *status) = 0;
+ virtual unsigned char readReadSelect_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readReadSelect_Module(tRioStatusCode *status) = 0;
+ virtual bool readReadSelect_Averaged(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLatchOutput_IfaceConstants;
+
+ virtual void strobeLatchOutput(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tAI(const tAI&);
+ void operator=(const tAI&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_AI_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tAccumulator.h b/aos/externals/WPILib/WPILib/ChipObject/tAccumulator.h
new file mode 100644
index 0000000..370848c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tAccumulator.h
@@ -0,0 +1,87 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Accumulator_h__
+#define __nFRC_2012_1_6_4_Accumulator_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tAccumulator
+{
+public:
+ tAccumulator(){}
+ virtual ~tAccumulator(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAccumulator* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 2,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ signed long long Value;
+ unsigned Count : 32;
+ };
+ struct{
+ unsigned value : 32;
+ unsigned value2 : 32;
+ unsigned value3 : 32;
+ };
+ } tOutput;
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(tRioStatusCode *status) = 0;
+ virtual signed long long readOutput_Value(tRioStatusCode *status) = 0;
+ virtual unsigned int readOutput_Count(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tCenter_IfaceConstants;
+
+ virtual void writeCenter(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readCenter(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReset_IfaceConstants;
+
+ virtual void strobeReset(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDeadband_IfaceConstants;
+
+ virtual void writeDeadband(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readDeadband(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tAccumulator(const tAccumulator&);
+ void operator=(const tAccumulator&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Accumulator_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tAlarm.h b/aos/externals/WPILib/WPILib/ChipObject/tAlarm.h
new file mode 100644
index 0000000..2e542a2
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tAlarm.h
@@ -0,0 +1,57 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Alarm_h__
+#define __nFRC_2012_1_6_4_Alarm_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tAlarm
+{
+public:
+ tAlarm(){}
+ virtual ~tAlarm(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAlarm* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ } tTriggerTime_IfaceConstants;
+
+ virtual void writeTriggerTime(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readTriggerTime(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tEnable_IfaceConstants;
+
+ virtual void writeEnable(bool value, tRioStatusCode *status) = 0;
+ virtual bool readEnable(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tAlarm(const tAlarm&);
+ void operator=(const tAlarm&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Alarm_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tAnalogTrigger.h b/aos/externals/WPILib/WPILib/ChipObject/tAnalogTrigger.h
new file mode 100644
index 0000000..a05f19d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tAnalogTrigger.h
@@ -0,0 +1,117 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_AnalogTrigger_h__
+#define __nFRC_2012_1_6_4_AnalogTrigger_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tAnalogTrigger
+{
+public:
+ tAnalogTrigger(){}
+ virtual ~tAnalogTrigger(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAnalogTrigger* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 8,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ unsigned InHysteresis : 1;
+ unsigned OverLimit : 1;
+ unsigned Rising : 1;
+ unsigned Falling : 1;
+ };
+ struct{
+ unsigned value : 4;
+ };
+ } tOutput;
+ typedef
+ union{
+ struct{
+ unsigned Channel : 3;
+ unsigned Module : 1;
+ unsigned Averaged : 1;
+ unsigned Filter : 1;
+ unsigned FloatingRollover : 1;
+ signed RolloverLimit : 8;
+ };
+ struct{
+ unsigned value : 15;
+ };
+ } tSourceSelect;
+
+
+ typedef enum
+ {
+ } tSourceSelect_IfaceConstants;
+
+ virtual void writeSourceSelect(tSourceSelect value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_Averaged(bool value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_Filter(bool value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_FloatingRollover(bool value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_RolloverLimit(signed short value, tRioStatusCode *status) = 0;
+ virtual tSourceSelect readSourceSelect(tRioStatusCode *status) = 0;
+ virtual unsigned char readSourceSelect_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readSourceSelect_Module(tRioStatusCode *status) = 0;
+ virtual bool readSourceSelect_Averaged(tRioStatusCode *status) = 0;
+ virtual bool readSourceSelect_Filter(tRioStatusCode *status) = 0;
+ virtual bool readSourceSelect_FloatingRollover(tRioStatusCode *status) = 0;
+ virtual signed short readSourceSelect_RolloverLimit(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tUpperLimit_IfaceConstants;
+
+ virtual void writeUpperLimit(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readUpperLimit(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLowerLimit_IfaceConstants;
+
+ virtual void writeLowerLimit(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readLowerLimit(tRioStatusCode *status) = 0;
+
+
+
+ typedef enum
+ {
+ kNumOutputElements = 8,
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_InHysteresis(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_OverLimit(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_Rising(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_Falling(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tAnalogTrigger(const tAnalogTrigger&);
+ void operator=(const tAnalogTrigger&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_AnalogTrigger_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tCounter.h b/aos/externals/WPILib/WPILib/ChipObject/tCounter.h
new file mode 100644
index 0000000..83d409b
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tCounter.h
@@ -0,0 +1,182 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Counter_h__
+#define __nFRC_2012_1_6_4_Counter_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tCounter
+{
+public:
+ tCounter(){}
+ virtual ~tCounter(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tCounter* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 8,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ unsigned Direction : 1;
+ signed Value : 31;
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tOutput;
+ typedef
+ union{
+ struct{
+ unsigned UpSource_Channel : 4;
+ unsigned UpSource_Module : 1;
+ unsigned UpSource_AnalogTrigger : 1;
+ unsigned DownSource_Channel : 4;
+ unsigned DownSource_Module : 1;
+ unsigned DownSource_AnalogTrigger : 1;
+ unsigned IndexSource_Channel : 4;
+ unsigned IndexSource_Module : 1;
+ unsigned IndexSource_AnalogTrigger : 1;
+ unsigned IndexActiveHigh : 1;
+ unsigned UpRisingEdge : 1;
+ unsigned UpFallingEdge : 1;
+ unsigned DownRisingEdge : 1;
+ unsigned DownFallingEdge : 1;
+ unsigned Mode : 2;
+ unsigned PulseLengthThreshold : 6;
+ unsigned Enable : 1;
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+ unsigned Period : 23;
+ signed Count : 8;
+ unsigned Stalled : 1;
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerOutput;
+ typedef
+ union{
+ struct{
+ unsigned StallPeriod : 24;
+ unsigned AverageSize : 7;
+ unsigned UpdateWhenEmpty : 1;
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerConfig;
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(tRioStatusCode *status) = 0;
+ virtual bool readOutput_Direction(tRioStatusCode *status) = 0;
+ virtual signed int readOutput_Value(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexActiveHigh(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpRisingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpFallingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownRisingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownFallingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Mode(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_PulseLengthThreshold(unsigned short value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_UpSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_UpSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_UpSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_DownSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_DownSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_DownSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexActiveHigh(tRioStatusCode *status) = 0;
+ virtual bool readConfig_UpRisingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_UpFallingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_DownRisingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_DownFallingEdge(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_Mode(tRioStatusCode *status) = 0;
+ virtual unsigned short readConfig_PulseLengthThreshold(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReset_IfaceConstants;
+
+ virtual void strobeReset(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerOutput_IfaceConstants;
+
+ virtual tTimerOutput readTimerOutput(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerOutput_Period(tRioStatusCode *status) = 0;
+ virtual signed char readTimerOutput_Count(tRioStatusCode *status) = 0;
+ virtual bool readTimerOutput_Stalled(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerConfig_IfaceConstants;
+
+ virtual void writeTimerConfig(tTimerConfig value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_StallPeriod(unsigned int value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_AverageSize(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_UpdateWhenEmpty(bool value, tRioStatusCode *status) = 0;
+ virtual tTimerConfig readTimerConfig(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerConfig_StallPeriod(tRioStatusCode *status) = 0;
+ virtual unsigned char readTimerConfig_AverageSize(tRioStatusCode *status) = 0;
+ virtual bool readTimerConfig_UpdateWhenEmpty(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tCounter(const tCounter&);
+ void operator=(const tCounter&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Counter_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tDIO.h b/aos/externals/WPILib/WPILib/ChipObject/tDIO.h
new file mode 100644
index 0000000..909e72c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tDIO.h
@@ -0,0 +1,296 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_DIO_h__
+#define __nFRC_2012_1_6_4_DIO_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tDIO
+{
+public:
+ tDIO(){}
+ virtual ~tDIO(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tDIO* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 2,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ unsigned Period : 16;
+ unsigned MinHigh : 16;
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tPWMConfig;
+ typedef
+ union{
+ struct{
+ unsigned RelayFwd : 8;
+ unsigned RelayRev : 8;
+ unsigned I2CHeader : 4;
+ };
+ struct{
+ unsigned value : 20;
+ };
+ } tSlowValue;
+ typedef
+ union{
+ struct{
+ unsigned Transaction : 1;
+ unsigned Done : 1;
+ unsigned Aborted : 1;
+ unsigned DataReceivedHigh : 24;
+ };
+ struct{
+ unsigned value : 27;
+ };
+ } tI2CStatus;
+ typedef
+ union{
+ struct{
+ unsigned PeriodPower : 4;
+ unsigned OutputSelect_0 : 4;
+ unsigned OutputSelect_1 : 4;
+ unsigned OutputSelect_2 : 4;
+ unsigned OutputSelect_3 : 4;
+ };
+ struct{
+ unsigned value : 20;
+ };
+ } tDO_PWMConfig;
+ typedef
+ union{
+ struct{
+ unsigned Address : 8;
+ unsigned BytesToRead : 3;
+ unsigned BytesToWrite : 3;
+ unsigned DataToSendHigh : 16;
+ unsigned BitwiseHandshake : 1;
+ };
+ struct{
+ unsigned value : 31;
+ };
+ } tI2CConfig;
+
+
+ typedef enum
+ {
+ } tI2CDataToSend_IfaceConstants;
+
+ virtual void writeI2CDataToSend(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readI2CDataToSend(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDO_IfaceConstants;
+
+ virtual void writeDO(unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readDO(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumFilterSelectElements = 16,
+ } tFilterSelect_IfaceConstants;
+
+ virtual void writeFilterSelect(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readFilterSelect(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumFilterPeriodElements = 3,
+ } tFilterPeriod_IfaceConstants;
+
+ virtual void writeFilterPeriod(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readFilterPeriod(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tOutputEnable_IfaceConstants;
+
+ virtual void writeOutputEnable(unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readOutputEnable(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tSlowValue_IfaceConstants;
+
+ virtual void writeSlowValue(tSlowValue value, tRioStatusCode *status) = 0;
+ virtual void writeSlowValue_RelayFwd(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeSlowValue_RelayRev(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeSlowValue_I2CHeader(unsigned char value, tRioStatusCode *status) = 0;
+ virtual tSlowValue readSlowValue(tRioStatusCode *status) = 0;
+ virtual unsigned char readSlowValue_RelayFwd(tRioStatusCode *status) = 0;
+ virtual unsigned char readSlowValue_RelayRev(tRioStatusCode *status) = 0;
+ virtual unsigned char readSlowValue_I2CHeader(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tI2CStatus_IfaceConstants;
+
+ virtual tI2CStatus readI2CStatus(tRioStatusCode *status) = 0;
+ virtual unsigned char readI2CStatus_Transaction(tRioStatusCode *status) = 0;
+ virtual bool readI2CStatus_Done(tRioStatusCode *status) = 0;
+ virtual bool readI2CStatus_Aborted(tRioStatusCode *status) = 0;
+ virtual unsigned int readI2CStatus_DataReceivedHigh(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tI2CDataReceived_IfaceConstants;
+
+ virtual unsigned int readI2CDataReceived(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDI_IfaceConstants;
+
+ virtual unsigned short readDI(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tPulse_IfaceConstants;
+
+ virtual void writePulse(unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readPulse(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumPWMPeriodScaleElements = 10,
+ } tPWMPeriodScale_IfaceConstants;
+
+ virtual void writePWMPeriodScale(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPWMPeriodScale(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumDO_PWMDutyCycleElements = 4,
+ } tDO_PWMDutyCycle_IfaceConstants;
+
+ virtual void writeDO_PWMDutyCycle(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMDutyCycle(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tBFL_IfaceConstants;
+
+ virtual void writeBFL(bool value, tRioStatusCode *status) = 0;
+ virtual bool readBFL(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tI2CStart_IfaceConstants;
+
+ virtual void strobeI2CStart(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDO_PWMConfig_IfaceConstants;
+
+ virtual void writeDO_PWMConfig(tDO_PWMConfig value, tRioStatusCode *status) = 0;
+ virtual void writeDO_PWMConfig_PeriodPower(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeDO_PWMConfig_OutputSelect_0(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeDO_PWMConfig_OutputSelect_1(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeDO_PWMConfig_OutputSelect_2(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeDO_PWMConfig_OutputSelect_3(unsigned char value, tRioStatusCode *status) = 0;
+ virtual tDO_PWMConfig readDO_PWMConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMConfig_PeriodPower(tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMConfig_OutputSelect_0(tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMConfig_OutputSelect_1(tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMConfig_OutputSelect_2(tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMConfig_OutputSelect_3(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tPulseLength_IfaceConstants;
+
+ virtual void writePulseLength(unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPulseLength(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tI2CConfig_IfaceConstants;
+
+ virtual void writeI2CConfig(tI2CConfig value, tRioStatusCode *status) = 0;
+ virtual void writeI2CConfig_Address(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeI2CConfig_BytesToRead(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeI2CConfig_BytesToWrite(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeI2CConfig_DataToSendHigh(unsigned short value, tRioStatusCode *status) = 0;
+ virtual void writeI2CConfig_BitwiseHandshake(bool value, tRioStatusCode *status) = 0;
+ virtual tI2CConfig readI2CConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readI2CConfig_Address(tRioStatusCode *status) = 0;
+ virtual unsigned char readI2CConfig_BytesToRead(tRioStatusCode *status) = 0;
+ virtual unsigned char readI2CConfig_BytesToWrite(tRioStatusCode *status) = 0;
+ virtual unsigned short readI2CConfig_DataToSendHigh(tRioStatusCode *status) = 0;
+ virtual bool readI2CConfig_BitwiseHandshake(tRioStatusCode *status) = 0;
+
+
+
+ typedef enum
+ {
+ } tLoopTiming_IfaceConstants;
+
+ virtual unsigned short readLoopTiming(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tPWMConfig_IfaceConstants;
+
+ virtual void writePWMConfig(tPWMConfig value, tRioStatusCode *status) = 0;
+ virtual void writePWMConfig_Period(unsigned short value, tRioStatusCode *status) = 0;
+ virtual void writePWMConfig_MinHigh(unsigned short value, tRioStatusCode *status) = 0;
+ virtual tPWMConfig readPWMConfig(tRioStatusCode *status) = 0;
+ virtual unsigned short readPWMConfig_Period(tRioStatusCode *status) = 0;
+ virtual unsigned short readPWMConfig_MinHigh(tRioStatusCode *status) = 0;
+
+
+
+ typedef enum
+ {
+ kNumPWMValueRegisters = 10,
+ } tPWMValue_IfaceConstants;
+
+ virtual void writePWMValue(unsigned char reg_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPWMValue(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+
+private:
+ tDIO(const tDIO&);
+ void operator=(const tDIO&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_DIO_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tDMA.h b/aos/externals/WPILib/WPILib/ChipObject/tDMA.h
new file mode 100644
index 0000000..68fbb92
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tDMA.h
@@ -0,0 +1,157 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_DMA_h__
+#define __nFRC_2012_1_6_4_DMA_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tDMA
+{
+public:
+ tDMA(){}
+ virtual ~tDMA(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tDMA* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ unsigned Pause : 1;
+ unsigned Enable_AI0_Low : 1;
+ unsigned Enable_AI0_High : 1;
+ unsigned Enable_AIAveraged0_Low : 1;
+ unsigned Enable_AIAveraged0_High : 1;
+ unsigned Enable_AI1_Low : 1;
+ unsigned Enable_AI1_High : 1;
+ unsigned Enable_AIAveraged1_Low : 1;
+ unsigned Enable_AIAveraged1_High : 1;
+ unsigned Enable_Accumulator0 : 1;
+ unsigned Enable_Accumulator1 : 1;
+ unsigned Enable_DI : 1;
+ unsigned Enable_AnalogTriggers : 1;
+ unsigned Enable_Counters_Low : 1;
+ unsigned Enable_Counters_High : 1;
+ unsigned Enable_CounterTimers_Low : 1;
+ unsigned Enable_CounterTimers_High : 1;
+ unsigned Enable_Encoders : 1;
+ unsigned Enable_EncoderTimers : 1;
+ unsigned ExternalClock : 1;
+ };
+ struct{
+ unsigned value : 20;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+ unsigned ExternalClockSource_Channel : 4;
+ unsigned ExternalClockSource_Module : 1;
+ unsigned ExternalClockSource_AnalogTrigger : 1;
+ unsigned RisingEdge : 1;
+ unsigned FallingEdge : 1;
+ };
+ struct{
+ unsigned value : 8;
+ };
+ } tExternalTriggers;
+
+
+
+ typedef enum
+ {
+ } tRate_IfaceConstants;
+
+ virtual void writeRate(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readRate(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Pause(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI0_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI0_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged0_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged0_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI1_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI1_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged1_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged1_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Accumulator0(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Accumulator1(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_DI(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AnalogTriggers(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Counters_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Counters_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_CounterTimers_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_CounterTimers_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Encoders(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_EncoderTimers(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ExternalClock(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Pause(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI0_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI0_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged0_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged0_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI1_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI1_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged1_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged1_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Accumulator0(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Accumulator1(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_DI(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AnalogTriggers(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Counters_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Counters_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_CounterTimers_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_CounterTimers_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Encoders(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_EncoderTimers(tRioStatusCode *status) = 0;
+ virtual bool readConfig_ExternalClock(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumExternalTriggersElements = 4,
+ } tExternalTriggers_IfaceConstants;
+
+ virtual void writeExternalTriggers(unsigned char bitfield_index, tExternalTriggers value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_ExternalClockSource_Channel(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_ExternalClockSource_Module(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_ExternalClockSource_AnalogTrigger(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_RisingEdge(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_FallingEdge(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;
+ virtual tExternalTriggers readExternalTriggers(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual unsigned char readExternalTriggers_ExternalClockSource_Channel(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual unsigned char readExternalTriggers_ExternalClockSource_Module(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readExternalTriggers_ExternalClockSource_AnalogTrigger(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readExternalTriggers_RisingEdge(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readExternalTriggers_FallingEdge(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tDMA(const tDMA&);
+ void operator=(const tDMA&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_DMA_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tDMAManager.h b/aos/externals/WPILib/WPILib/ChipObject/tDMAManager.h
new file mode 100644
index 0000000..edc774a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tDMAManager.h
@@ -0,0 +1,47 @@
+// Class for handling DMA transters.
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+
+#ifndef __tDMAManager_h__
+#define __tDMAManager_h__
+
+#include "NiRio.h"
+#include "tSystem.h"
+
+namespace nFPGA
+{
+// TODO: Implement DMA Manager
+/*
+class tDMAManager : public tSystem
+{
+public:
+ tDMAManager(tNIRIO_u32 dmaChannel, tNIRIO_u32 hostBufferSize, tRioStatusCode *status);
+ ~tDMAManager();
+ void start(tRioStatusCode *status);
+ void stop(tRioStatusCode *status);
+ bool isStarted() {return _started;}
+ void read(
+ tNIRIO_u32* buf,
+ tNIRIO_u32 num,
+ tNIRIO_u32 timeout,
+ tNIRIO_u32* read,
+ tNIRIO_u32* remaining,
+ tRioStatusCode *status);
+ void write(
+ tNIRIO_u32* buf,
+ tNIRIO_u32 num,
+ tNIRIO_u32 timeout,
+ tNIRIO_u32* remaining,
+ tRioStatusCode *status);
+private:
+ bool _started;
+ tNIRIO_u32 _dmaChannel;
+ tNIRIO_u32 _hostBufferSize;
+ tDMAChannelDescriptor const *_dmaChannelDescriptor;
+
+};
+*/
+}
+
+
+#endif // __tDMAManager_h__
+
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tEncoder.h b/aos/externals/WPILib/WPILib/ChipObject/tEncoder.h
new file mode 100644
index 0000000..53a770a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tEncoder.h
@@ -0,0 +1,167 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Encoder_h__
+#define __nFRC_2012_1_6_4_Encoder_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tEncoder
+{
+public:
+ tEncoder(){}
+ virtual ~tEncoder(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tEncoder* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 4,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ unsigned Direction : 1;
+ signed Value : 31;
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tOutput;
+ typedef
+ union{
+ struct{
+ unsigned ASource_Channel : 4;
+ unsigned ASource_Module : 1;
+ unsigned ASource_AnalogTrigger : 1;
+ unsigned BSource_Channel : 4;
+ unsigned BSource_Module : 1;
+ unsigned BSource_AnalogTrigger : 1;
+ unsigned IndexSource_Channel : 4;
+ unsigned IndexSource_Module : 1;
+ unsigned IndexSource_AnalogTrigger : 1;
+ unsigned IndexActiveHigh : 1;
+ unsigned Reverse : 1;
+ unsigned Enable : 1;
+ };
+ struct{
+ unsigned value : 21;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+ unsigned Period : 23;
+ signed Count : 8;
+ unsigned Stalled : 1;
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerOutput;
+ typedef
+ union{
+ struct{
+ unsigned StallPeriod : 24;
+ unsigned AverageSize : 7;
+ unsigned UpdateWhenEmpty : 1;
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerConfig;
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(tRioStatusCode *status) = 0;
+ virtual bool readOutput_Direction(tRioStatusCode *status) = 0;
+ virtual signed int readOutput_Value(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ASource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ASource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ASource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_BSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_BSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_BSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexActiveHigh(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Reverse(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_ASource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_ASource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_ASource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_BSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_BSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_BSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexActiveHigh(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Reverse(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReset_IfaceConstants;
+
+ virtual void strobeReset(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerOutput_IfaceConstants;
+
+ virtual tTimerOutput readTimerOutput(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerOutput_Period(tRioStatusCode *status) = 0;
+ virtual signed char readTimerOutput_Count(tRioStatusCode *status) = 0;
+ virtual bool readTimerOutput_Stalled(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerConfig_IfaceConstants;
+
+ virtual void writeTimerConfig(tTimerConfig value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_StallPeriod(unsigned int value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_AverageSize(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_UpdateWhenEmpty(bool value, tRioStatusCode *status) = 0;
+ virtual tTimerConfig readTimerConfig(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerConfig_StallPeriod(tRioStatusCode *status) = 0;
+ virtual unsigned char readTimerConfig_AverageSize(tRioStatusCode *status) = 0;
+ virtual bool readTimerConfig_UpdateWhenEmpty(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tEncoder(const tEncoder&);
+ void operator=(const tEncoder&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Encoder_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tGlobal.h b/aos/externals/WPILib/WPILib/ChipObject/tGlobal.h
new file mode 100644
index 0000000..19faf8d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tGlobal.h
@@ -0,0 +1,70 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Global_h__
+#define __nFRC_2012_1_6_4_Global_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tGlobal
+{
+public:
+ tGlobal(){}
+ virtual ~tGlobal(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tGlobal* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ } tVersion_IfaceConstants;
+
+ virtual unsigned short readVersion(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tFPGA_LED_IfaceConstants;
+
+ virtual void writeFPGA_LED(bool value, tRioStatusCode *status) = 0;
+ virtual bool readFPGA_LED(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLocalTime_IfaceConstants;
+
+ virtual unsigned int readLocalTime(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tRevision_IfaceConstants;
+
+ virtual unsigned int readRevision(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tGlobal(const tGlobal&);
+ void operator=(const tGlobal&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Global_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tInterrupt.h b/aos/externals/WPILib/WPILib/ChipObject/tInterrupt.h
new file mode 100644
index 0000000..319591d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tInterrupt.h
@@ -0,0 +1,84 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Interrupt_h__
+#define __nFRC_2012_1_6_4_Interrupt_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tInterrupt
+{
+public:
+ tInterrupt(){}
+ virtual ~tInterrupt(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tInterrupt* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 8,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ unsigned Source_Channel : 4;
+ unsigned Source_Module : 1;
+ unsigned Source_AnalogTrigger : 1;
+ unsigned RisingEdge : 1;
+ unsigned FallingEdge : 1;
+ unsigned WaitForAck : 1;
+ };
+ struct{
+ unsigned value : 9;
+ };
+ } tConfig;
+
+
+ typedef enum
+ {
+ } tTimeStamp_IfaceConstants;
+
+ virtual unsigned int readTimeStamp(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Source_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Source_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Source_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_RisingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_FallingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_WaitForAck(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_Source_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_Source_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Source_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual bool readConfig_RisingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_FallingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_WaitForAck(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tInterrupt(const tInterrupt&);
+ void operator=(const tInterrupt&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Interrupt_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tInterruptManager.h b/aos/externals/WPILib/WPILib/ChipObject/tInterruptManager.h
new file mode 100644
index 0000000..d7e96a2
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tInterruptManager.h
@@ -0,0 +1,50 @@
+// Class for handling interrupts.
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+
+#ifndef __tInterruptManager_h__
+#define __tInterruptManager_h__
+
+#include "NiRio.h"
+#include "tSystem.h"
+#include <semLib.h>
+
+namespace nFPGA
+{
+
+typedef void (*tInterruptHandler)(uint32_t interruptAssertedMask, void *param);
+
+class tInterruptManager : public tSystem
+{
+public:
+ tInterruptManager(uint32_t interruptMask, bool watcher, tRioStatusCode *status);
+ ~tInterruptManager();
+ void registerHandler(tInterruptHandler handler, void *param, tRioStatusCode *status);
+ uint32_t watch(int32_t timeoutInMs, tRioStatusCode *status);
+ void enable(tRioStatusCode *status);
+ void disable(tRioStatusCode *status);
+ bool isEnabled(tRioStatusCode *status);
+private:
+ void handler();
+ static int handlerWrapper(tInterruptManager *pInterrupt);
+
+ void acknowledge(tRioStatusCode *status);
+ void reserve(tRioStatusCode *status);
+ void unreserve(tRioStatusCode *status);
+ tInterruptHandler _handler;
+ uint32_t _interruptMask;
+ int32_t _taskId;
+ NiFpga_IrqContext _rioContext;
+ bool _watcher;
+ bool _enabled;
+ void *_userParam;
+
+ // maintain the interrupts that are already dealt with.
+ static uint32_t _globalInterruptMask;
+ static SEM_ID _globalInterruptMaskSemaphore;
+};
+
+}
+
+
+#endif // __tInterruptManager_h__
+
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tSPI.h b/aos/externals/WPILib/WPILib/ChipObject/tSPI.h
new file mode 100644
index 0000000..f113604
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tSPI.h
@@ -0,0 +1,200 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_SPI_h__
+#define __nFRC_2012_1_6_4_SPI_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tSPI
+{
+public:
+ tSPI(){}
+ virtual ~tSPI(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tSPI* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ unsigned ReceivedDataOverflow : 1;
+ unsigned Idle : 1;
+ };
+ struct{
+ unsigned value : 2;
+ };
+ } tStatus;
+ typedef
+ union{
+ struct{
+ unsigned BusBitWidth : 8;
+ unsigned ClockHalfPeriodDelay : 8;
+ unsigned MSBfirst : 1;
+ unsigned DataOnFalling : 1;
+ unsigned LatchFirst : 1;
+ unsigned LatchLast : 1;
+ unsigned FramePolarity : 1;
+ unsigned WriteOnly : 1;
+ unsigned ClockPolarity : 1;
+ };
+ struct{
+ unsigned value : 23;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+ unsigned SCLK_Channel : 4;
+ unsigned SCLK_Module : 1;
+ unsigned MOSI_Channel : 4;
+ unsigned MOSI_Module : 1;
+ unsigned MISO_Channel : 4;
+ unsigned MISO_Module : 1;
+ unsigned SS_Channel : 4;
+ unsigned SS_Module : 1;
+ };
+ struct{
+ unsigned value : 20;
+ };
+ } tChannels;
+
+
+
+ typedef enum
+ {
+ } tStatus_IfaceConstants;
+
+ virtual tStatus readStatus(tRioStatusCode *status) = 0;
+ virtual bool readStatus_ReceivedDataOverflow(tRioStatusCode *status) = 0;
+ virtual bool readStatus_Idle(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReadReceivedData_IfaceConstants;
+
+ virtual void strobeReadReceivedData(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_BusBitWidth(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ClockHalfPeriodDelay(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_MSBfirst(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DataOnFalling(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_LatchFirst(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_LatchLast(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_FramePolarity(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_WriteOnly(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ClockPolarity(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_BusBitWidth(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_ClockHalfPeriodDelay(tRioStatusCode *status) = 0;
+ virtual bool readConfig_MSBfirst(tRioStatusCode *status) = 0;
+ virtual bool readConfig_DataOnFalling(tRioStatusCode *status) = 0;
+ virtual bool readConfig_LatchFirst(tRioStatusCode *status) = 0;
+ virtual bool readConfig_LatchLast(tRioStatusCode *status) = 0;
+ virtual bool readConfig_FramePolarity(tRioStatusCode *status) = 0;
+ virtual bool readConfig_WriteOnly(tRioStatusCode *status) = 0;
+ virtual bool readConfig_ClockPolarity(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReceivedData_IfaceConstants;
+
+ virtual unsigned int readReceivedData(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDataToLoad_IfaceConstants;
+
+ virtual void writeDataToLoad(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readDataToLoad(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReset_IfaceConstants;
+
+ virtual void strobeReset(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tChannels_IfaceConstants;
+
+ virtual void writeChannels(tChannels value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_SCLK_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_SCLK_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_MOSI_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_MOSI_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_MISO_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_MISO_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_SS_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_SS_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual tChannels readChannels(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_SCLK_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_SCLK_Module(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_MOSI_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_MOSI_Module(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_MISO_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_MISO_Module(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_SS_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_SS_Module(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tClearReceivedData_IfaceConstants;
+
+ virtual void strobeClearReceivedData(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReceivedElements_IfaceConstants;
+
+ virtual unsigned short readReceivedElements(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLoad_IfaceConstants;
+
+ virtual void strobeLoad(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tAvailableToLoad_IfaceConstants;
+
+ virtual unsigned short readAvailableToLoad(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tSPI(const tSPI&);
+ void operator=(const tSPI&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_SPI_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tSolenoid.h b/aos/externals/WPILib/WPILib/ChipObject/tSolenoid.h
new file mode 100644
index 0000000..67c9a40
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tSolenoid.h
@@ -0,0 +1,50 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Solenoid_h__
+#define __nFRC_2012_1_6_4_Solenoid_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tSolenoid
+{
+public:
+ tSolenoid(){}
+ virtual ~tSolenoid(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tSolenoid* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ kNumDO7_0Elements = 2,
+ } tDO7_0_IfaceConstants;
+
+ virtual void writeDO7_0(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readDO7_0(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tSolenoid(const tSolenoid&);
+ void operator=(const tSolenoid&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Solenoid_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tSystem.h b/aos/externals/WPILib/WPILib/ChipObject/tSystem.h
new file mode 100644
index 0000000..b5dccf0
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tSystem.h
@@ -0,0 +1,47 @@
+// Base class for generated chip objects
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+
+#ifndef __tSystem_h__
+#define __tSystem_h__
+
+#include "NiRio.h"
+#include <vxWorks.h>
+
+#define FRC_FPGA_PRELOAD_BITFILE
+
+typedef uint32_t NiFpga_Session;
+
+namespace nFPGA
+{
+
+class tSystem
+{
+public:
+ tSystem(tRioStatusCode *status);
+ ~tSystem();
+ void getFpgaGuid(uint32_t *guid_ptr, tRioStatusCode *status);
+
+protected:
+ static NiFpga_Session _DeviceHandle;
+
+#ifdef FRC_FPGA_PRELOAD_BITFILE
+ void NiFpga_SharedOpen_common(const char* bitfile);
+ NiFpga_Status NiFpga_SharedOpen(const char* bitfile,
+ const char* signature,
+ const char* resource,
+ uint32_t attribute,
+ NiFpga_Session* session);
+ NiFpga_Status NiFpgaLv_SharedOpen(const char* const bitfile,
+ const char* const apiSignature,
+ const char* const resource,
+ const uint32_t attribute,
+ NiFpga_Session* const session);
+private:
+ static char *_FileName;
+ static char *_Bitfile;
+#endif
+};
+
+}
+
+#endif // __tSystem_h__
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tSystemInterface.h b/aos/externals/WPILib/WPILib/ChipObject/tSystemInterface.h
new file mode 100644
index 0000000..46786e8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tSystemInterface.h
@@ -0,0 +1,26 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+
+#ifndef __tSystemInterface_h__
+#define __tSystemInterface_h__
+
+namespace nFPGA
+{
+
+class tSystemInterface
+{
+public:
+ tSystemInterface(){}
+ virtual ~tSystemInterface(){}
+
+ virtual const uint16_t getExpectedFPGAVersion()=0;
+ virtual const uint32_t getExpectedFPGARevision()=0;
+ virtual const uint32_t * const getExpectedFPGASignature()=0;
+ virtual void getHardwareFpgaSignature(uint32_t *guid_ptr, tRioStatusCode *status)=0;
+ virtual uint32_t getLVHandle(tRioStatusCode *status)=0;
+ virtual uint32_t getHandle()=0;
+};
+
+}
+
+#endif // __tSystemInterface_h__
+
diff --git a/aos/externals/WPILib/WPILib/ChipObject/tWatchdog.h b/aos/externals/WPILib/WPILib/ChipObject/tWatchdog.h
new file mode 100644
index 0000000..f5ef16a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ChipObject/tWatchdog.h
@@ -0,0 +1,101 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Watchdog_h__
+#define __nFRC_2012_1_6_4_Watchdog_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tWatchdog
+{
+public:
+ tWatchdog(){}
+ virtual ~tWatchdog(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tWatchdog* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ unsigned SystemActive : 1;
+ unsigned Alive : 1;
+ unsigned SysDisableCount : 15;
+ unsigned DisableCount : 15;
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tStatus;
+
+
+
+ typedef enum
+ {
+ } tStatus_IfaceConstants;
+
+ virtual tStatus readStatus(tRioStatusCode *status) = 0;
+ virtual bool readStatus_SystemActive(tRioStatusCode *status) = 0;
+ virtual bool readStatus_Alive(tRioStatusCode *status) = 0;
+ virtual unsigned short readStatus_SysDisableCount(tRioStatusCode *status) = 0;
+ virtual unsigned short readStatus_DisableCount(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tImmortal_IfaceConstants;
+
+ virtual void writeImmortal(bool value, tRioStatusCode *status) = 0;
+ virtual bool readImmortal(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tKill_IfaceConstants;
+
+ virtual void strobeKill(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tFeed_IfaceConstants;
+
+ virtual void strobeFeed(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tExpiration_IfaceConstants;
+
+ virtual void writeExpiration(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readExpiration(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimer_IfaceConstants;
+
+ virtual unsigned int readTimer(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tWatchdog(const tWatchdog&);
+ void operator=(const tWatchdog&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Watchdog_h__
diff --git a/aos/externals/WPILib/WPILib/Commands/Command.cpp b/aos/externals/WPILib/WPILib/Commands/Command.cpp
new file mode 100644
index 0000000..b037977
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/Command.cpp
@@ -0,0 +1,457 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/Command.h"
+#include "Commands/CommandGroup.h"
+#include "Commands/Scheduler.h"
+#include "DriverStation.h"
+#include "NetworkTables/NetworkTable.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+
+static const char *kName = "name";
+static const char *kRunning = "running";
+static const char *kIsParented = "isParented";
+
+void Command::InitCommand(const char *name, double timeout)
+{
+ m_timeout = timeout;
+ m_locked = false;
+ m_startTime = -1;
+ m_initialized = false;
+ m_running = false;
+ m_interruptible = true;
+ m_canceled = false;
+ m_runWhenDisabled = false;
+ m_parent = NULL;
+ m_table = NULL;
+ if (name == NULL)
+ {
+ // Don't have a way to find the subclass name like java, so use the address
+ char buf[32];
+ snprintf(buf, 32, "Command_%p", this);
+ m_name = buf;
+ }
+ else
+ {
+ m_name = name;
+ }
+}
+
+/**
+ * Creates a new command.
+ * The name of this command will be default.
+ */
+Command::Command()
+{
+ InitCommand(NULL, -1.0);
+}
+
+/**
+ * Creates a new command with the given name and no timeout.
+ * @param name the name for this command
+ */
+Command::Command(const char *name)
+{
+ if (name == NULL)
+ wpi_setWPIErrorWithContext(NullParameter, "name");
+ InitCommand(name, -1.0);
+}
+
+/**
+ * Creates a new command with the given timeout and a default name.
+ * @param timeout the time (in seconds) before this command "times out"
+ * @see Command#isTimedOut() isTimedOut()
+ */
+Command::Command(double timeout)
+{
+ if (timeout < 0.0)
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0");
+ InitCommand(NULL, timeout);
+}
+
+/**
+ * Creates a new command with the given name and timeout.
+ * @param name the name of the command
+ * @param timeout the time (in seconds) before this command "times out"
+ * @see Command#isTimedOut() isTimedOut()
+ */
+Command::Command(const char *name, double timeout)
+{
+ if (name == NULL)
+ wpi_setWPIErrorWithContext(NullParameter, "name");
+ if (timeout < 0.0)
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0");
+ InitCommand(name, timeout);
+}
+
+Command::~Command()
+{
+ if (m_table != NULL)
+ {
+ m_table->RemoveChangeListener(kRunning, this);
+ }
+}
+
+/**
+ * Sets the timeout of this command.
+ * @param timeout the timeout (in seconds)
+ * @see Command#isTimedOut() isTimedOut()
+ */
+void Command::SetTimeout(double timeout)
+{
+ if (timeout < 0.0)
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0");
+ else
+ m_timeout = timeout;
+}
+
+/**
+ * Returns the time since this command was initialized (in seconds).
+ * This function will work even if there is no specified timeout.
+ * @return the time since this command was initialized (in seconds).
+ */
+double Command::TimeSinceInitialized()
+{
+ if (m_startTime < 0.0)
+ return 0.0;
+ else
+ return Timer::GetFPGATimestamp() - m_startTime;
+}
+
+/**
+ * This method specifies that the given {@link Subsystem} is used by this command.
+ * This method is crucial to the functioning of the Command System in general.
+ *
+ * <p>Note that the recommended way to call this method is in the constructor.</p>
+ *
+ * @param subsystem the {@link Subsystem} required
+ * @see Subsystem
+ */
+void Command::Requires(Subsystem *subsystem)
+{
+ if (!AssertUnlocked("Can not add new requirement to command"))
+ return;
+
+ if (subsystem != NULL)
+ m_requirements.insert(subsystem);
+ else
+ wpi_setWPIErrorWithContext(NullParameter, "subsystem");
+}
+
+/**
+ * Called when the command has been removed.
+ * This will call {@link Command#interrupted() interrupted()} or {@link Command#end() end()}.
+ */
+void Command::Removed()
+{
+ if (m_initialized)
+ {
+ if (IsCanceled())
+ {
+ Interrupted();
+ _Interrupted();
+ }
+ else
+ {
+ End();
+ _End();
+ }
+ }
+ m_initialized = false;
+ m_canceled = false;
+ m_running = false;
+ if (m_table != NULL)
+ m_table->PutBoolean(kRunning, false);
+}
+
+/**
+ * Starts up the command. Gets the command ready to start.
+ * <p>Note that the command will eventually start, however it will not necessarily
+ * do so immediately, and may in fact be canceled before initialize is even called.</p>
+ */
+void Command::Start()
+{
+ LockChanges();
+ if (m_parent != NULL)
+ wpi_setWPIErrorWithContext(CommandIllegalUse, "Can not start a command that is part of a command group");
+
+ Scheduler::GetInstance()->AddCommand(this);
+}
+
+/**
+ * The run method is used internally to actually run the commands.
+ * @return whether or not the command should stay within the {@link Scheduler}.
+ */
+bool Command::Run()
+{
+ if (!m_runWhenDisabled && m_parent == NULL && DriverStation::GetInstance()->IsDisabled())
+ Cancel();
+
+ if (IsCanceled())
+ return false;
+
+ if (!m_initialized)
+ {
+ m_initialized = true;
+ StartTiming();
+ _Initialize();
+ Initialize();
+ }
+ _Execute();
+ Execute();
+ return !IsFinished();
+}
+
+void Command::_Initialize()
+{
+}
+
+void Command::_Interrupted()
+{
+}
+
+void Command::_Execute()
+{
+}
+
+void Command::_End()
+{
+}
+
+/**
+ * Called to indicate that the timer should start.
+ * This is called right before {@link Command#initialize() initialize()} is, inside the
+ * {@link Command#run() run()} method.
+ */
+void Command::StartTiming()
+{
+ m_startTime = Timer::GetFPGATimestamp();
+}
+
+/**
+ * Returns whether or not the {@link Command#timeSinceInitialized() timeSinceInitialized()}
+ * method returns a number which is greater than or equal to the timeout for the command.
+ * If there is no timeout, this will always return false.
+ * @return whether the time has expired
+ */
+bool Command::IsTimedOut()
+{
+ return m_timeout != -1 && TimeSinceInitialized() >= m_timeout;
+}
+
+/**
+ * Returns the requirements (as an std::set of {@link Subsystem Subsystems} pointers) of this command
+ * @return the requirements (as an std::set of {@link Subsystem Subsystems} pointers) of this command
+ */
+Command::SubsystemSet Command::GetRequirements()
+{
+ return m_requirements;
+}
+
+/**
+ * Prevents further changes from being made
+ */
+void Command::LockChanges()
+{
+ m_locked = true;
+}
+
+/**
+ * If changes are locked, then this will generate a CommandIllegalUse error.
+ * @param message the message to report on error (it is appended by a default message)
+ * @return true if assert passed, false if assert failed
+ */
+bool Command::AssertUnlocked(const char *message)
+{
+ if (m_locked)
+ {
+ char buf[128];
+ snprintf(buf, 128, "%s after being started or being added to a command group", message);
+ wpi_setWPIErrorWithContext(CommandIllegalUse, buf);
+ return false;
+ }
+ return true;
+}
+
+/**
+ * Sets the parent of this command. No actual change is made to the group.
+ * @param parent the parent
+ */
+void Command::SetParent(CommandGroup *parent)
+{
+ if (parent == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "parent");
+ }
+ else if (m_parent != NULL)
+ {
+ wpi_setWPIErrorWithContext(CommandIllegalUse, "Can not give command to a command group after already being put in a command group");
+ }
+ else
+ {
+ LockChanges();
+ m_parent = parent;
+ if (m_table != NULL)
+ {
+ m_table->PutBoolean(kIsParented, true);
+ }
+ }
+}
+
+/**
+ * This is used internally to mark that the command has been started.
+ * The lifecycle of a command is:
+ *
+ * startRunning() is called.
+ * run() is called (multiple times potentially)
+ * removed() is called
+ *
+ * It is very important that startRunning and removed be called in order or some assumptions
+ * of the code will be broken.
+ */
+void Command::StartRunning()
+{
+ m_running = true;
+ m_startTime = -1;
+ if (m_table != NULL)
+ m_table->PutBoolean(kRunning, true);
+}
+
+/**
+ * Returns whether or not the command is running.
+ * This may return true even if the command has just been canceled, as it may
+ * not have yet called {@link Command#interrupted()}.
+ * @return whether or not the command is running
+ */
+bool Command::IsRunning()
+{
+ return m_running;
+}
+
+/**
+ * This will cancel the current command.
+ * <p>This will cancel the current command eventually. It can be called multiple times.
+ * And it can be called when the command is not running. If the command is running though,
+ * then the command will be marked as canceled and eventually removed.</p>
+ * <p>A command can not be canceled
+ * if it is a part of a command group, you must cancel the command group instead.</p>
+ */
+void Command::Cancel()
+{
+ if (m_parent != NULL)
+ wpi_setWPIErrorWithContext(CommandIllegalUse, "Can not cancel a command that is part of a command group");
+
+ _Cancel();
+}
+
+/**
+ * This works like cancel(), except that it doesn't throw an exception if it is a part
+ * of a command group. Should only be called by the parent command group.
+ */
+void Command::_Cancel()
+{
+ if (IsRunning())
+ m_canceled = true;
+}
+
+/**
+ * Returns whether or not this has been canceled.
+ * @return whether or not this has been canceled
+ */
+bool Command::IsCanceled()
+{
+ return m_canceled;
+}
+
+/**
+ * Returns whether or not this command can be interrupted.
+ * @return whether or not this command can be interrupted
+ */
+bool Command::IsInterruptible()
+{
+ return m_interruptible;
+}
+
+/**
+ * Sets whether or not this command can be interrupted.
+ * @param interruptible whether or not this command can be interrupted
+ */
+void Command::SetInterruptible(bool interruptible)
+{
+ m_interruptible = interruptible;
+}
+
+/**
+ * Checks if the command requires the given {@link Subsystem}.
+ * @param system the system
+ * @return whether or not the subsystem is required (false if given NULL)
+ */
+bool Command::DoesRequire(Subsystem *system)
+{
+ return m_requirements.count(system) > 0;
+}
+
+/**
+ * Returns the {@link CommandGroup} that this command is a part of.
+ * Will return null if this {@link Command} is not in a group.
+ * @return the {@link CommandGroup} that this command is a part of (or null if not in group)
+ */
+CommandGroup *Command::GetGroup()
+{
+ return m_parent;
+}
+
+/**
+ * Sets whether or not this {@link Command} should run when the robot is disabled.
+ *
+ * <p>By default a command will not run when the robot is disabled, and will in fact be canceled.</p>
+ * @param run whether or not this command should run when the robot is disabled
+ */
+void Command::SetRunWhenDisabled(bool run)
+{
+ m_runWhenDisabled = run;
+}
+
+/**
+ * Returns whether or not this {@link Command} will run when the robot is disabled, or if it will cancel itself.
+ * @return whether or not this {@link Command} will run when the robot is disabled, or if it will cancel itself
+ */
+bool Command::WillRunWhenDisabled()
+{
+ return m_runWhenDisabled;
+}
+
+std::string Command::GetName()
+{
+ return m_name;
+}
+
+std::string Command::GetType()
+{
+ return "Command";
+}
+
+NetworkTable *Command::GetTable()
+{
+ if (m_table == NULL)
+ {
+ m_table = new NetworkTable();
+ m_table->PutString(kName, GetName());
+ m_table->PutBoolean(kRunning, IsRunning());
+ m_table->PutBoolean(kIsParented, m_parent != NULL);
+ m_table->AddChangeListener(kRunning, this);
+ }
+ return m_table;
+}
+
+void Command::ValueChanged(NetworkTable *table, const char *name, NetworkTables_Types type)
+{
+ if (table->GetBoolean(kRunning))
+ Start();
+ else
+ Cancel();
+}
diff --git a/aos/externals/WPILib/WPILib/Commands/Command.h b/aos/externals/WPILib/WPILib/Commands/Command.h
new file mode 100644
index 0000000..ddfd677
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/Command.h
@@ -0,0 +1,162 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __COMMAND_H__
+#define __COMMAND_H__
+
+#include "ErrorBase.h"
+#include "NetworkTables/NetworkTableChangeListener.h"
+#include "SmartDashboard/SmartDashboardNamedData.h"
+#include <set>
+#include <string>
+
+class CommandGroup;
+class NetworkTable;
+class Subsystem;
+
+/**
+ * The Command class is at the very core of the entire command framework.
+ * Every command can be started with a call to {@link Command#Start() Start()}.
+ * Once a command is started it will call {@link Command#Initialize() Initialize()}, and then
+ * will repeatedly call {@link Command#Execute() Execute()} until the {@link Command#IsFinished() IsFinished()}
+ * returns true. Once it does, {@link Command#End() End()} will be called.
+ *
+ * <p>However, if at any point while it is running {@link Command#Cancel() Cancel()} is called, then
+ * the command will be stopped and {@link Command#Interrupted() Interrupted()} will be called.</p>
+ *
+ * <p>If a command uses a {@link Subsystem}, then it should specify that it does so by
+ * calling the {@link Command#Requires(Subsystem) Requires(...)} method
+ * in its constructor. Note that a Command may have multiple requirements, and
+ * {@link Command#Requires(Subsystem) Requires(...)} should be
+ * called for each one.</p>
+ *
+ * <p>If a command is running and a new command with shared requirements is started,
+ * then one of two things will happen. If the active command is interruptible,
+ * then {@link Command#Cancel() Cancel()} will be called and the command will be removed
+ * to make way for the new one. If the active command is not interruptible, the
+ * other one will not even be started, and the active one will continue functioning.</p>
+ *
+ * @see CommandGroup
+ * @see Subsystem
+ */
+class Command : public SmartDashboardNamedData, public NetworkTableChangeListener, public ErrorBase
+{
+ friend class CommandGroup;
+ friend class Scheduler;
+public:
+ Command();
+ Command(const char *name);
+ Command(double timeout);
+ Command(const char *name, double timeout);
+ virtual ~Command();
+ double TimeSinceInitialized();
+ void Requires(Subsystem *s);
+ bool IsCanceled();
+ void Start();
+ bool Run();
+ void Cancel();
+ bool IsRunning();
+ bool IsInterruptible();
+ void SetInterruptible(bool interruptible);
+ bool DoesRequire(Subsystem *subsystem);
+ typedef std::set<Subsystem *> SubsystemSet;
+ SubsystemSet GetRequirements();
+ CommandGroup *GetGroup();
+ void SetRunWhenDisabled(bool run);
+ bool WillRunWhenDisabled();
+
+ virtual std::string GetName();
+ virtual std::string GetType();
+ virtual NetworkTable *GetTable();
+
+ virtual void ValueChanged(NetworkTable *table, const char *name, NetworkTables_Types type);
+ virtual void ValueConfirmed(NetworkTable *table, const char *name, NetworkTables_Types type) {}
+
+protected:
+ void SetTimeout(double timeout);
+ bool IsTimedOut();
+ bool AssertUnlocked(const char *message);
+ void SetParent(CommandGroup *parent);
+ /**
+ * The initialize method is called the first time this Command is run after
+ * being started.
+ */
+ virtual void Initialize() = 0;
+ /**
+ * The execute method is called repeatedly until this Command either finishes
+ * or is canceled.
+ */
+ virtual void Execute() = 0;
+ /**
+ * Returns whether this command is finished.
+ * If it is, then the command will be removed
+ * and {@link Command#end() end()} will be called.
+ *
+ * <p>It may be useful for a team to reference the {@link Command#isTimedOut() isTimedOut()} method
+ * for time-sensitive commands.</p>
+ * @return whether this command is finished.
+ * @see Command#isTimedOut() isTimedOut()
+ */
+ virtual bool IsFinished() = 0;
+ /**
+ * Called when the command ended peacefully. This is where you may want
+ * to wrap up loose ends, like shutting off a motor that was being used
+ * in the command.
+ */
+ virtual void End() = 0;
+ /**
+ * Called when the command ends because somebody called {@link Command#cancel() cancel()}
+ * or another command shared the same requirements as this one, and booted
+ * it out.
+ *
+ * <p>This is where you may want
+ * to wrap up loose ends, like shutting off a motor that was being used
+ * in the command.</p>
+ *
+ * <p>Generally, it is useful to simply call the {@link Command#end() end()} method
+ * within this method</p>
+ */
+ virtual void Interrupted() = 0;
+ virtual void _Initialize();
+ virtual void _Interrupted();
+ virtual void _Execute();
+ virtual void _End();
+ virtual void _Cancel();
+
+private:
+ void InitCommand(const char *name, double timeout);
+ void LockChanges();
+ /*synchronized*/ void Removed();
+ void StartRunning();
+ void StartTiming();
+
+ /** The name of this command */
+ std::string m_name;
+ /** The time since this command was initialized */
+ double m_startTime;
+ /** The time (in seconds) before this command "times out" (or -1 if no timeout) */
+ double m_timeout;
+ /** Whether or not this command has been initialized */
+ bool m_initialized;
+ /** The requirements (or null if no requirements) */
+ SubsystemSet m_requirements;
+ /** Whether or not it is running */
+ bool m_running;
+ /** Whether or not it is interruptible*/
+ bool m_interruptible;
+ /** Whether or not it has been canceled */
+ bool m_canceled;
+ /** Whether or not it has been locked */
+ bool m_locked;
+ /** Whether this command should run when the robot is disabled */
+ bool m_runWhenDisabled;
+ /** The {@link CommandGroup} this is in */
+ CommandGroup *m_parent;
+
+ NetworkTable *m_table;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Commands/CommandGroup.cpp b/aos/externals/WPILib/WPILib/Commands/CommandGroup.cpp
new file mode 100644
index 0000000..b1decd3
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/CommandGroup.cpp
@@ -0,0 +1,383 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/CommandGroup.h"
+#include "WPIErrors.h"
+
+/**
+ * Creates a new {@link CommandGroup CommandGroup}.
+ */
+CommandGroup::CommandGroup()
+{
+ m_currentCommandIndex = -1;
+}
+
+/**
+ * Creates a new {@link CommandGroup CommandGroup} with the given name.
+ * @param name the name for this command group
+ */
+CommandGroup::CommandGroup(const char *name) :
+ Command(name)
+{
+ m_currentCommandIndex = -1;
+}
+
+CommandGroup::~CommandGroup()
+{
+}
+
+/**
+ * Adds a new {@link Command Command} to the group. The {@link Command Command} will be started after
+ * all the previously added {@link Command Commands}.
+ *
+ * <p>Note that any requirements the given {@link Command Command} has will be added to the
+ * group. For this reason, a {@link Command Command's} requirements can not be changed after
+ * being added to a group.</p>
+ *
+ * <p>It is recommended that this method be called in the constructor.</p>
+ *
+ * @param command The {@link Command Command} to be added
+ */
+void CommandGroup::AddSequential(Command *command)
+{
+ if (command == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "command");
+ return;
+ }
+ if (!AssertUnlocked("Cannot add new command to command group"))
+ return;
+
+ command->SetParent(this);
+
+ m_commands.push_back(CommandGroupEntry(command, CommandGroupEntry::kSequence_InSequence));
+ // Iterate through command->GetRequirements() and call Requires() on each required subsystem
+ Command::SubsystemSet requirements = command->GetRequirements();
+ Command::SubsystemSet::iterator iter = requirements.begin();
+ for (; iter != requirements.end(); iter++)
+ Requires(*iter);
+}
+
+/**
+ * Adds a new {@link Command Command} to the group with a given timeout.
+ * The {@link Command Command} will be started after all the previously added commands.
+ *
+ * <p>Once the {@link Command Command} is started, it will be run until it finishes or the time
+ * expires, whichever is sooner. Note that the given {@link Command Command} will have no
+ * knowledge that it is on a timer.</p>
+ *
+ * <p>Note that any requirements the given {@link Command Command} has will be added to the
+ * group. For this reason, a {@link Command Command's} requirements can not be changed after
+ * being added to a group.</p>
+ *
+ * <p>It is recommended that this method be called in the constructor.</p>
+ *
+ * @param command The {@link Command Command} to be added
+ * @param timeout The timeout (in seconds)
+ */
+void CommandGroup::AddSequential(Command *command, double timeout)
+{
+ if (command == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "command");
+ return;
+ }
+ if (!AssertUnlocked("Cannot add new command to command group"))
+ return;
+ if (timeout < 0.0)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0");
+ return;
+ }
+
+ command->SetParent(this);
+
+ m_commands.push_back(CommandGroupEntry(command, CommandGroupEntry::kSequence_InSequence, timeout));
+ // Iterate through command->GetRequirements() and call Requires() on each required subsystem
+ Command::SubsystemSet requirements = command->GetRequirements();
+ Command::SubsystemSet::iterator iter = requirements.begin();
+ for (; iter != requirements.end(); iter++)
+ Requires(*iter);
+}
+
+/**
+ * Adds a new child {@link Command} to the group. The {@link Command} will be started after
+ * all the previously added {@link Command Commands}.
+ *
+ * <p>Instead of waiting for the child to finish, a {@link CommandGroup} will have it
+ * run at the same time as the subsequent {@link Command Commands}. The child will run until either
+ * it finishes, a new child with conflicting requirements is started, or
+ * the main sequence runs a {@link Command} with conflicting requirements. In the latter
+ * two cases, the child will be canceled even if it says it can't be
+ * interrupted.</p>
+ *
+ * <p>Note that any requirements the given {@link Command Command} has will be added to the
+ * group. For this reason, a {@link Command Command's} requirements can not be changed after
+ * being added to a group.</p>
+ *
+ * <p>It is recommended that this method be called in the constructor.</p>
+ *
+ * @param command The command to be added
+ */
+void CommandGroup::AddParallel(Command *command)
+{
+ if (command == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "command");
+ return;
+ }
+ if (!AssertUnlocked("Cannot add new command to command group"))
+ return;
+
+ command->SetParent(this);
+
+ m_commands.push_back(CommandGroupEntry(command, CommandGroupEntry::kSequence_BranchChild));
+ // Iterate through command->GetRequirements() and call Requires() on each required subsystem
+ Command::SubsystemSet requirements = command->GetRequirements();
+ Command::SubsystemSet::iterator iter = requirements.begin();
+ for (; iter != requirements.end(); iter++)
+ Requires(*iter);
+}
+
+/**
+ * Adds a new child {@link Command} to the group with the given timeout. The {@link Command} will be started after
+ * all the previously added {@link Command Commands}.
+ *
+ * <p>Once the {@link Command Command} is started, it will run until it finishes, is interrupted,
+ * or the time expires, whichever is sooner. Note that the given {@link Command Command} will have no
+ * knowledge that it is on a timer.</p>
+ *
+ * <p>Instead of waiting for the child to finish, a {@link CommandGroup} will have it
+ * run at the same time as the subsequent {@link Command Commands}. The child will run until either
+ * it finishes, the timeout expires, a new child with conflicting requirements is started, or
+ * the main sequence runs a {@link Command} with conflicting requirements. In the latter
+ * two cases, the child will be canceled even if it says it can't be
+ * interrupted.</p>
+ *
+ * <p>Note that any requirements the given {@link Command Command} has will be added to the
+ * group. For this reason, a {@link Command Command's} requirements can not be changed after
+ * being added to a group.</p>
+ *
+ * <p>It is recommended that this method be called in the constructor.</p>
+ *
+ * @param command The command to be added
+ * @param timeout The timeout (in seconds)
+ */
+void CommandGroup::AddParallel(Command *command, double timeout)
+{
+ if (command == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "command");
+ return;
+ }
+ if (!AssertUnlocked("Cannot add new command to command group"))
+ return;
+ if (timeout < 0.0)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0");
+ return;
+ }
+
+ command->SetParent(this);
+
+ m_commands.push_back(CommandGroupEntry(command, CommandGroupEntry::kSequence_BranchChild, timeout));
+ // Iterate through command->GetRequirements() and call Requires() on each required subsystem
+ Command::SubsystemSet requirements = command->GetRequirements();
+ Command::SubsystemSet::iterator iter = requirements.begin();
+ for (; iter != requirements.end(); iter++)
+ Requires(*iter);
+}
+
+void CommandGroup::_Initialize()
+{
+ m_currentCommandIndex = -1;
+}
+
+void CommandGroup::_Execute()
+{
+ CommandGroupEntry entry;
+ Command *cmd = NULL;
+ bool firstRun = false;
+
+ if (m_currentCommandIndex == -1)
+ {
+ firstRun = true;
+ m_currentCommandIndex = 0;
+ }
+
+ while ((unsigned)m_currentCommandIndex < m_commands.size())
+ {
+ if (cmd != NULL)
+ {
+ if (entry.IsTimedOut())
+ cmd->_Cancel();
+
+ if (cmd->Run())
+ {
+ break;
+ }
+ else
+ {
+ cmd->Removed();
+ m_currentCommandIndex++;
+ firstRun = true;
+ cmd = NULL;
+ continue;
+ }
+ }
+
+ entry = m_commands[m_currentCommandIndex];
+ cmd = NULL;
+
+ switch (entry.m_state)
+ {
+ case CommandGroupEntry::kSequence_InSequence:
+ cmd = entry.m_command;
+ if (firstRun)
+ {
+ cmd->StartRunning();
+ CancelConflicts(cmd);
+ firstRun = false;
+ }
+ break;
+
+ case CommandGroupEntry::kSequence_BranchPeer:
+ m_currentCommandIndex++;
+ entry.m_command->Start();
+ break;
+
+ case CommandGroupEntry::kSequence_BranchChild:
+ m_currentCommandIndex++;
+ CancelConflicts(entry.m_command);
+ entry.m_command->StartRunning();
+ m_children.push_back(entry);
+ break;
+ }
+ }
+
+ // Run Children
+ CommandList::iterator iter = m_children.begin();
+ for (; iter != m_children.end();)
+ {
+ entry = *iter;
+ Command *child = entry.m_command;
+ if (entry.IsTimedOut())
+ child->_Cancel();
+
+ if (!child->Run())
+ {
+ child->Removed();
+ iter = m_children.erase(iter);
+ }
+ else
+ {
+ iter++;
+ }
+ }
+}
+
+void CommandGroup::_End()
+{
+ // Theoretically, we don't have to check this, but we do if teams override the IsFinished method
+ if (m_currentCommandIndex != -1 && (unsigned)m_currentCommandIndex < m_commands.size())
+ {
+ Command *cmd = m_commands[m_currentCommandIndex].m_command;
+ cmd->_Cancel();
+ cmd->Removed();
+ }
+
+ CommandList::iterator iter = m_children.begin();
+ for (; iter != m_children.end(); iter++)
+ {
+ Command *cmd = iter->m_command;
+ cmd->_Cancel();
+ cmd->Removed();
+ }
+ m_children.clear();
+}
+
+void CommandGroup::_Interrupted()
+{
+ _End();
+}
+
+// Can be overwritten by teams
+void CommandGroup::Initialize()
+{
+}
+
+// Can be overwritten by teams
+void CommandGroup::Execute()
+{
+}
+
+// Can be overwritten by teams
+void CommandGroup::End()
+{
+}
+
+// Can be overwritten by teams
+void CommandGroup::Interrupted()
+{
+}
+
+bool CommandGroup::IsFinished()
+{
+ return (unsigned)m_currentCommandIndex >= m_commands.size() && m_children.empty();
+}
+
+bool CommandGroup::IsInterruptible()
+{
+ if (!Command::IsInterruptible())
+ return false;
+
+ if (m_currentCommandIndex != -1 && (unsigned)m_currentCommandIndex < m_commands.size())
+ {
+ Command *cmd = m_commands[m_currentCommandIndex].m_command;
+ if (!cmd->IsInterruptible())
+ return false;
+ }
+
+ CommandList::iterator iter = m_children.begin();
+ for (; iter != m_children.end(); iter++)
+ {
+ if (!iter->m_command->IsInterruptible())
+ return false;
+ }
+
+ return true;
+}
+
+void CommandGroup::CancelConflicts(Command *command)
+{
+ CommandList::iterator childIter = m_children.begin();
+ for (; childIter != m_children.end();)
+ {
+ Command *child = childIter->m_command;
+ bool erased = false;
+
+ Command::SubsystemSet requirements = command->GetRequirements();
+ Command::SubsystemSet::iterator requirementIter = requirements.begin();
+ for (; requirementIter != requirements.end(); requirementIter++)
+ {
+ if (child->DoesRequire(*requirementIter))
+ {
+ child->_Cancel();
+ child->Removed();
+ childIter = m_children.erase(childIter);
+ erased = true;
+ break;
+ }
+ }
+ if (!erased)
+ childIter++;
+ }
+}
+
+int CommandGroup::GetSize()
+{
+ return m_children.size();
+}
diff --git a/aos/externals/WPILib/WPILib/Commands/CommandGroup.h b/aos/externals/WPILib/WPILib/Commands/CommandGroup.h
new file mode 100644
index 0000000..87c299f
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/CommandGroup.h
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __COMMAND_GROUP_H__
+#define __COMMAND_GROUP_H__
+
+#include "Commands/Command.h"
+#include "Commands/CommandGroupEntry.h"
+#include <list>
+#include <vector>
+
+/**
+ * A {@link CommandGroup} is a list of commands which are executed in sequence.
+ *
+ * <p>Commands in a {@link CommandGroup} are added using the {@link CommandGroup#AddSequential(Command) AddSequential(...)} method
+ * and are called sequentially.
+ * {@link CommandGroup CommandGroups} are themselves {@link Command Commands}
+ * and can be given to other {@link CommandGroup CommandGroups}.</p>
+ *
+ * <p>{@link CommandGroup CommandGroups} will carry all of the requirements of their {@link Command subcommands}. Additional
+ * requirements can be specified by calling {@link CommandGroup#Requires(Subsystem) Requires(...)}
+ * normally in the constructor.</P>
+ *
+ * <p>CommandGroups can also execute commands in parallel, simply by adding them
+ * using {@link CommandGroup#AddParallel(Command) AddParallel(...)}.</p>
+ *
+ * @see Command
+ * @see Subsystem
+ */
+class CommandGroup : public Command
+{
+public:
+ CommandGroup();
+ CommandGroup(const char *name);
+ virtual ~CommandGroup();
+
+ void AddSequential(Command *command);
+ void AddSequential(Command *command, double timeout);
+ void AddParallel(Command *command);
+ void AddParallel(Command *command, double timeout);
+ bool IsInterruptible();
+ int GetSize();
+
+protected:
+ virtual void Initialize();
+ virtual void Execute();
+ virtual bool IsFinished();
+ virtual void End();
+ virtual void Interrupted();
+ virtual void _Initialize();
+ virtual void _Interrupted();
+ virtual void _Execute();
+ virtual void _End();
+
+private:
+ void CancelConflicts(Command *command);
+
+ typedef std::vector<CommandGroupEntry> CommandVector;
+ /** The commands in this group (stored in entries) */
+ CommandVector m_commands;
+ typedef std::list<CommandGroupEntry> CommandList;
+ /** The active children in this group (stored in entries) */
+ CommandList m_children;
+ /** The current command, -1 signifies that none have been run */
+ int m_currentCommandIndex;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Commands/CommandGroupEntry.cpp b/aos/externals/WPILib/WPILib/Commands/CommandGroupEntry.cpp
new file mode 100644
index 0000000..1448257
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/CommandGroupEntry.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/CommandGroupEntry.h"
+
+#include "Commands/Command.h"
+
+CommandGroupEntry::CommandGroupEntry() :
+ m_timeout(-1.0),
+ m_command(NULL),
+ m_state(kSequence_InSequence)
+{
+}
+
+CommandGroupEntry::CommandGroupEntry(Command *command, Sequence state) :
+ m_timeout(-1.0),
+ m_command(command),
+ m_state(state)
+{
+}
+
+CommandGroupEntry::CommandGroupEntry(Command *command, Sequence state, double timeout) :
+ m_timeout(timeout),
+ m_command(command),
+ m_state(state)
+{
+}
+
+bool CommandGroupEntry::IsTimedOut()
+{
+ if (m_timeout < 0.0)
+ return false;
+ double time = m_command->TimeSinceInitialized();
+ if (time == 0.0)
+ return false;
+ return time >= m_timeout;
+}
diff --git a/aos/externals/WPILib/WPILib/Commands/CommandGroupEntry.h b/aos/externals/WPILib/WPILib/Commands/CommandGroupEntry.h
new file mode 100644
index 0000000..d2be6a8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/CommandGroupEntry.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __COMMAND_GROUP_ENTRY_H__
+#define __COMMAND_GROUP_ENTRY_H__
+
+class Command;
+
+class CommandGroupEntry
+{
+public:
+ typedef enum {kSequence_InSequence, kSequence_BranchPeer, kSequence_BranchChild} Sequence;
+
+ CommandGroupEntry();
+ CommandGroupEntry(Command *command, Sequence state);
+ CommandGroupEntry(Command *command, Sequence state, double timeout);
+ bool IsTimedOut();
+
+ double m_timeout;
+ Command *m_command;
+ Sequence m_state;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Commands/PIDCommand.cpp b/aos/externals/WPILib/WPILib/Commands/PIDCommand.cpp
new file mode 100644
index 0000000..d289164
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/PIDCommand.cpp
@@ -0,0 +1,122 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/PIDCommand.h"
+
+#include "SmartDashboard/SendablePIDController.h"
+#include "float.h"
+
+// XXX max and min are not used?
+
+PIDCommand::PIDCommand(const char *name, double p, double i, double d) :
+ Command(name)
+{
+ m_max = DBL_MAX;
+ m_min = DBL_MIN;
+ m_controller = new SendablePIDController(p, i, d, this, this);
+}
+
+PIDCommand::PIDCommand(const char *name, double p, double i, double d, double period) :
+ Command(name)
+{
+ m_max = DBL_MAX;
+ m_min = DBL_MIN;
+ m_controller = new SendablePIDController(p, i, d, this, this, period);
+}
+
+PIDCommand::PIDCommand(double p, double i, double d)
+{
+ m_max = DBL_MAX;
+ m_min = DBL_MIN;
+ m_controller = new SendablePIDController(p, i, d, this, this);
+}
+
+PIDCommand::PIDCommand(double p, double i, double d, double period)
+{
+ m_max = DBL_MAX;
+ m_min = DBL_MIN;
+ m_controller = new SendablePIDController(p, i, d, this, this, period);
+}
+
+PIDCommand::~PIDCommand()
+{
+ delete m_controller;
+}
+
+void PIDCommand::_Initialize()
+{
+ m_controller->Enable();
+}
+
+void PIDCommand::_End()
+{
+ m_controller->Disable();
+}
+
+void PIDCommand::_Interrupted()
+{
+ _End();
+}
+
+void PIDCommand::SetSetpointRelative(double deltaSetpoint)
+{
+ SetSetpoint(GetSetpoint() + deltaSetpoint);
+}
+
+void PIDCommand::PIDWrite(float output)
+{
+ UsePIDOutput(output);
+}
+
+double PIDCommand::PIDGet()
+{
+ return ReturnPIDInput();
+}
+
+PIDController *PIDCommand::GetPIDController()
+{
+ return m_controller;
+}
+
+void PIDCommand::SetSetpoint(double setpoint)
+{
+ m_controller->SetSetpoint(setpoint);
+}
+
+double PIDCommand::GetSetpoint()
+{
+ return m_controller->GetSetpoint();
+}
+
+double PIDCommand::GetPosition()
+{
+ return ReturnPIDInput();
+}
+
+void PIDCommand::SetSetpointRange(double a, double b)
+{
+ if (a <= b)
+ {
+ m_min = a;
+ m_max = b;
+ }
+ else
+ {
+ m_min = b;
+ m_max = a;
+ }
+}
+
+std::string PIDCommand::GetType()
+{
+ return "PIDCommand";
+}
+
+NetworkTable *PIDCommand::GetControllerTable()
+{
+ return m_controller->GetTable();
+}
+
diff --git a/aos/externals/WPILib/WPILib/Commands/PIDCommand.h b/aos/externals/WPILib/WPILib/Commands/PIDCommand.h
new file mode 100644
index 0000000..9e503b9
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/PIDCommand.h
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __PID_COMMAND_H__
+#define __PID_COMMAND_H__
+
+#include "Commands/Command.h"
+#include "PIDSource.h"
+#include "PIDOutput.h"
+
+class NetworkTable;
+class PIDController;
+class SendablePIDController;
+
+class PIDCommand : public Command, public PIDOutput, public PIDSource
+{
+public:
+ PIDCommand(const char *name, double p, double i, double d);
+ PIDCommand(const char *name, double p, double i, double d, double period);
+ PIDCommand(double p, double i, double d);
+ PIDCommand(double p, double i, double d, double period);
+ virtual ~PIDCommand();
+
+ void SetSetpointRelative(double deltaSetpoint);
+
+ // PIDOutput interface
+ virtual void PIDWrite(float output);
+
+ // PIDSource interface
+ virtual double PIDGet();
+
+ NetworkTable *GetControllerTable();
+
+ virtual std::string GetType();
+protected:
+ PIDController *GetPIDController();
+ virtual void _Initialize();
+ virtual void _Interrupted();
+ virtual void _End();
+ void SetSetpoint(double setpoint);
+ double GetSetpoint();
+ double GetPosition();
+ void SetSetpointRange(double a, double b);
+
+ virtual double ReturnPIDInput() = 0;
+ virtual void UsePIDOutput(double output) = 0;
+
+private:
+ /** The max setpoint value */
+ double m_max;
+ /** The min setpoint value */
+ double m_min;
+ /** The internal {@link PIDController} */
+ SendablePIDController *m_controller;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Commands/PIDSubsystem.cpp b/aos/externals/WPILib/WPILib/Commands/PIDSubsystem.cpp
new file mode 100644
index 0000000..b600cb9
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/PIDSubsystem.cpp
@@ -0,0 +1,118 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/PIDSubsystem.h"
+#include "SmartDashboard/SendablePIDController.h"
+#include "float.h"
+
+// XXX max and min are not used?
+
+PIDSubsystem::PIDSubsystem(const char *name, double p, double i, double d) :
+ Subsystem(name)
+{
+ m_max = DBL_MAX;
+ m_min = DBL_MIN;
+ m_controller = new SendablePIDController(p, i, d, this, this);
+}
+
+PIDSubsystem::PIDSubsystem(const char *name, double p, double i, double d,
+ double period) :
+ Subsystem(name)
+{
+ m_max = DBL_MAX;
+ m_min = DBL_MIN;
+ m_controller = new SendablePIDController(p, i, d, this, this, period);
+}
+
+PIDSubsystem::PIDSubsystem(double p, double i, double d) :
+ Subsystem("PIDSubsystem")
+{
+ m_max = DBL_MAX;
+ m_min = DBL_MIN;
+ m_controller = new SendablePIDController(p, i, d, this, this);
+}
+
+PIDSubsystem::PIDSubsystem(double p, double i, double d, double period) :
+ Subsystem("PIDSubsystem")
+{
+ m_max = DBL_MAX;
+ m_min = DBL_MIN;
+ m_controller = new SendablePIDController(p, i, d, this, this, period);
+}
+
+PIDSubsystem::~PIDSubsystem()
+{
+ delete m_controller;
+}
+
+void PIDSubsystem::Enable()
+{
+ m_controller->Enable();
+}
+
+void PIDSubsystem::Disable()
+{
+ m_controller->Disable();
+}
+
+std::string PIDSubsystem::GetType()
+{
+ return "PIDSubsystem";
+}
+
+NetworkTable *PIDSubsystem::GetControllerTable()
+{
+ return m_controller->GetTable();
+}
+
+PIDController *PIDSubsystem::GetPIDController()
+{
+ return m_controller;
+}
+
+void PIDSubsystem::SetSetpoint(double setpoint)
+{
+ m_controller->SetSetpoint(setpoint);
+}
+
+void PIDSubsystem::SetSetpointRelative(double deltaSetpoint)
+{
+ SetSetpoint(GetSetpoint() + deltaSetpoint);
+}
+
+double PIDSubsystem::GetSetpoint()
+{
+ return m_controller->GetSetpoint();
+}
+
+double PIDSubsystem::GetPosition()
+{
+ return ReturnPIDInput();
+}
+
+void PIDSubsystem::SetSetpointRange(double a, double b)
+{
+ if (a <= b)
+ {
+ m_min = a;
+ m_max = b;
+ }
+ else
+ {
+ m_min = b;
+ m_max = a;
+ }
+}
+
+void PIDSubsystem::PIDWrite(float output)
+{
+ UsePIDOutput(output);
+}
+
+double PIDSubsystem::PIDGet()
+{
+ return ReturnPIDInput();
+}
diff --git a/aos/externals/WPILib/WPILib/Commands/PIDSubsystem.h b/aos/externals/WPILib/WPILib/Commands/PIDSubsystem.h
new file mode 100644
index 0000000..32c2925
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/PIDSubsystem.h
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __PID_SUBSYSTEM_H__
+#define __PID_SUBSYSTEM_H__
+
+#include "Commands/Subsystem.h"
+#include "PIDController.h"
+#include "PIDSource.h"
+#include "PIDOutput.h"
+
+class NetworkTable;
+class SendablePIDController;
+
+class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource
+{
+public:
+ PIDSubsystem(const char *name, double p, double i, double d);
+ PIDSubsystem(const char *name, double p, double i, double d, double period);
+ PIDSubsystem(double p, double i, double d);
+ PIDSubsystem(double p, double i, double d, double period);
+ virtual ~PIDSubsystem();
+
+ void Enable();
+ void Disable();
+ NetworkTable *GetControllerTable();
+
+ // SmartDashboardData interface
+ virtual std::string GetType();
+
+ // PIDOutput interface
+ virtual void PIDWrite(float output);
+
+ // PIDSource interface
+ virtual double PIDGet();
+ void SetSetpoint(double setpoint);
+ void SetSetpointRelative(double deltaSetpoint);
+ double GetSetpoint();
+ double GetPosition();
+ void SetSetpointRange(double a, double b);
+
+protected:
+ PIDController *GetPIDController();
+
+ virtual double ReturnPIDInput() = 0;
+ virtual void UsePIDOutput(double output) = 0;
+
+private:
+ /** The max setpoint value */
+ double m_max;
+ /** The min setpoint value */
+ double m_min;
+ /** The internal {@link PIDController} */
+ SendablePIDController *m_controller;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Commands/PrintCommand.cpp b/aos/externals/WPILib/WPILib/Commands/PrintCommand.cpp
new file mode 100644
index 0000000..4a84996
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/PrintCommand.cpp
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/PrintCommand.h"
+#include "stdio.h"
+#include <sstream>
+
+PrintCommand::PrintCommand(const char *message) :
+ Command(((std::stringstream&)(std::stringstream("Print \"") << message << "\"")).str().c_str())
+{
+ m_message = message;
+}
+
+void PrintCommand::Initialize()
+{
+ printf(m_message.c_str());
+}
+
+void PrintCommand::Execute()
+{
+}
+
+bool PrintCommand::IsFinished()
+{
+ return true;
+}
+
+void PrintCommand::End()
+{
+}
+
+void PrintCommand::Interrupted()
+{
+}
diff --git a/aos/externals/WPILib/WPILib/Commands/PrintCommand.h b/aos/externals/WPILib/WPILib/Commands/PrintCommand.h
new file mode 100644
index 0000000..b6342f5
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/PrintCommand.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __PRINT_COMMAND_H__
+#define __PRINT_COMMAND_H__
+
+#include "Commands/Command.h"
+#include <string>
+
+class PrintCommand : public Command
+{
+public:
+ PrintCommand(const char *message);
+ virtual ~PrintCommand() {}
+
+protected:
+ virtual void Initialize();
+ virtual void Execute();
+ virtual bool IsFinished();
+ virtual void End();
+ virtual void Interrupted();
+
+private:
+ std::string m_message;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Commands/Scheduler.cpp b/aos/externals/WPILib/WPILib/Commands/Scheduler.cpp
new file mode 100644
index 0000000..918a68f
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/Scheduler.cpp
@@ -0,0 +1,252 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/Scheduler.h"
+
+#include "Buttons/ButtonScheduler.h"
+#include "Commands/Subsystem.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "NetworkTables/NetworkTable.h"
+#include "Synchronized.h"
+#include "WPIErrors.h"
+#include <iostream>
+#include <set>
+#include <semLib.h>
+
+Scheduler *Scheduler::_instance = NULL;
+
+Scheduler::Scheduler() :
+ m_tableLock(NULL),
+ m_table(NULL),
+ m_buttonsLock(NULL),
+ m_additionsLock(NULL),
+ m_adding(false)
+{
+ m_tableLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+ m_buttonsLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+ m_additionsLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Command, nUsageReporting::kCommand_Scheduler);
+}
+
+Scheduler::~Scheduler()
+{
+ semTake(m_additionsLock, WAIT_FOREVER);
+ semDelete(m_additionsLock);
+
+ semTake(m_buttonsLock, WAIT_FOREVER);
+ semDelete(m_buttonsLock);
+
+ semTake(m_tableLock, WAIT_FOREVER);
+ semDelete(m_tableLock);
+}
+
+/**
+ * Returns the {@link Scheduler}, creating it if one does not exist.
+ * @return the {@link Scheduler}
+ */
+Scheduler *Scheduler::GetInstance()
+{
+ if (_instance == NULL)
+ _instance = new Scheduler();
+ return _instance;
+}
+
+void Scheduler::AddCommand(Command *command)
+{
+ Synchronized sync(m_additionsLock);
+ m_additions.push_back(command);
+}
+
+void Scheduler::AddButton(ButtonScheduler *button)
+{
+ Synchronized sync(m_buttonsLock);
+ m_buttons.push_back(button);
+}
+
+void Scheduler::ProcessCommandAddition(Command *command)
+{
+ if (command == NULL)
+ return;
+
+ // Check to make sure no adding during adding
+ if (m_adding)
+ {
+ wpi_setWPIErrorWithContext(IncompatibleState, "Can not start command from cancel method");
+ return;
+ }
+
+ // Only add if not already in
+ CommandSet::iterator found = m_commands.find(command);
+ if (found == m_commands.end())
+ {
+ // Check that the requirements can be had
+ Command::SubsystemSet requirements = command->GetRequirements();
+ Command::SubsystemSet::iterator iter;
+ for (iter = requirements.begin(); iter != requirements.end(); iter++)
+ {
+ Subsystem *lock = *iter;
+ if (lock->GetCurrentCommand() != NULL && !lock->GetCurrentCommand()->IsInterruptible())
+ return;
+ }
+
+ // Give it the requirements
+ m_adding = true;
+ for (iter = requirements.begin(); iter != requirements.end(); iter++)
+ {
+ Subsystem *lock = *iter;
+ if (lock->GetCurrentCommand() != NULL)
+ {
+ lock->GetCurrentCommand()->Cancel();
+ Remove(lock->GetCurrentCommand());
+ }
+ lock->SetCurrentCommand(command);
+ }
+ m_adding = false;
+
+ m_commands.insert(command);
+
+ command->StartRunning();
+ }
+}
+
+/**
+ * Runs a single iteration of the loop. This method should be called often in order to have a functioning
+ * {@link Command} system. The loop has five stages:
+ *
+ * <ol>
+ * <li> Poll the Buttons </li>
+ * <li> Execute/Remove the Commands </li>
+ * <li> Send values to SmartDashboard </li>
+ * <li> Add Commands </li>
+ * <li> Add Defaults </li>
+ * </ol>
+ */
+void Scheduler::Run()
+{
+ // Get button input (going backwards preserves button priority)
+ {
+ Synchronized sync(m_buttonsLock);
+ ButtonVector::reverse_iterator rButtonIter = m_buttons.rbegin();
+ for (; rButtonIter != m_buttons.rend(); rButtonIter++)
+ {
+ (*rButtonIter)->Execute();
+ }
+ }
+
+ // Loop through the commands
+ CommandSet::iterator commandIter = m_commands.begin();
+ for (; commandIter != m_commands.end();)
+ {
+ Command *command = *commandIter;
+ // Increment before potentially removing to keep the iterator valid
+ commandIter++;
+ if (!command->Run())
+ {
+ Remove(command);
+ }
+ }
+
+ // Send the value over the table
+ if (m_table != NULL) {
+ int count = 0;
+ Synchronized sync(m_tableLock);
+ m_table->BeginTransaction();
+ commandIter = m_commands.begin();
+ for (; commandIter != m_commands.end(); commandIter++)
+ {
+ char buf[10];
+ snprintf(buf, 10, "%d", ++count);
+ m_table->PutSubTable(buf, (*commandIter)->GetTable());
+ }
+ m_table->PutInt("count", count);
+ m_table->EndTransaction();
+ }
+
+ // Add the new things
+ {
+ Synchronized sync(m_additionsLock);
+ CommandVector::iterator additionsIter = m_additions.begin();
+ for (; additionsIter != m_additions.end(); additionsIter++)
+ {
+ ProcessCommandAddition(*additionsIter);
+ }
+ m_additions.clear();
+ }
+
+ // Add in the defaults
+ Command::SubsystemSet::iterator subsystemIter = m_subsystems.begin();
+ for (; subsystemIter != m_subsystems.end(); subsystemIter++)
+ {
+ Subsystem *lock = *subsystemIter;
+ if (lock->GetCurrentCommand() == NULL)
+ {
+ ProcessCommandAddition(lock->GetDefaultCommand());
+ }
+ lock->ConfirmCommand();
+ }
+}
+
+/**
+ * Registers a {@link Subsystem} to this {@link Scheduler}, so that the {@link Scheduler} might know
+ * if a default {@link Command} needs to be run. All {@link Subsystem Subsystems} should call this.
+ * @param system the system
+ */
+void Scheduler::RegisterSubsystem(Subsystem *subsystem)
+{
+ if (subsystem == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "subsystem");
+ return;
+ }
+ m_subsystems.insert(subsystem);
+}
+
+/**
+ * Removes the {@link Command} from the {@link Scheduler}.
+ * @param command the command to remove
+ */
+void Scheduler::Remove(Command *command)
+{
+ if (command == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "command");
+ return;
+ }
+
+ if (!m_commands.erase(command))
+ return;
+
+ Command::SubsystemSet requirements = command->GetRequirements();
+ Command::SubsystemSet::iterator iter = requirements.begin();
+ for (; iter != requirements.end(); iter++)
+ {
+ Subsystem *lock = *iter;
+ lock->SetCurrentCommand(NULL);
+ }
+
+ command->Removed();
+}
+
+std::string Scheduler::GetName()
+{
+ return "Scheduler";
+}
+
+std::string Scheduler::GetType()
+{
+ return "Scheduler";
+}
+
+NetworkTable *Scheduler::GetTable()
+{
+ if (m_table == NULL)
+ {
+ m_table = new NetworkTable();
+ m_table->PutInt("count", 0);
+ }
+ return m_table;
+}
diff --git a/aos/externals/WPILib/WPILib/Commands/Scheduler.h b/aos/externals/WPILib/WPILib/Commands/Scheduler.h
new file mode 100644
index 0000000..a70dc59
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/Scheduler.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SCHEDULER_H__
+#define __SCHEDULER_H__
+
+#include "Commands/Command.h"
+#include "ErrorBase.h"
+#include "SmartDashboard/SmartDashboardNamedData.h"
+#include <list>
+#include <map>
+#include <set>
+#include <vector>
+
+class ButtonScheduler;
+class NetworkTable;
+class Subsystem;
+
+class Scheduler : public SmartDashboardNamedData, public ErrorBase
+{
+public:
+ static Scheduler *GetInstance();
+
+ virtual std::string GetName();
+ virtual std::string GetType();
+ virtual NetworkTable *GetTable();
+
+ void AddCommand(Command* command);
+ void AddButton(ButtonScheduler* button);
+ void RegisterSubsystem(Subsystem *subsystem);
+ void Run();
+ void Remove(Command *command);
+
+private:
+ Scheduler();
+ virtual ~Scheduler();
+
+ void ProcessCommandAddition(Command *command);
+
+ static Scheduler *_instance;
+ SEM_ID m_tableLock;
+ NetworkTable *m_table;
+ Command::SubsystemSet m_subsystems;
+ SEM_ID m_buttonsLock;
+ typedef std::vector<ButtonScheduler *> ButtonVector;
+ ButtonVector m_buttons;
+ typedef std::vector<Command *> CommandVector;
+ SEM_ID m_additionsLock;
+ CommandVector m_additions;
+ typedef std::set<Command *> CommandSet;
+ CommandSet m_commands;
+ bool m_adding;
+};
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Commands/StartCommand.cpp b/aos/externals/WPILib/WPILib/Commands/StartCommand.cpp
new file mode 100644
index 0000000..4e04514
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/StartCommand.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/StartCommand.h"
+
+StartCommand::StartCommand(Command *commandToStart) :
+ Command("StartCommand")
+{
+ m_commandToFork = commandToStart;
+}
+
+void StartCommand::Initialize()
+{
+ m_commandToFork->Start();
+}
+
+void StartCommand::Execute()
+{
+}
+
+void StartCommand::End()
+{
+}
+
+void StartCommand::Interrupted()
+{
+}
+
+bool StartCommand::IsFinished()
+{
+ return true;
+}
diff --git a/aos/externals/WPILib/WPILib/Commands/StartCommand.h b/aos/externals/WPILib/WPILib/Commands/StartCommand.h
new file mode 100644
index 0000000..1ea6dcf
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/StartCommand.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __START_COMMAND_H__
+#define __START_COMMAND_H__
+
+#include "Commands/Command.h"
+
+class StartCommand : public Command
+{
+public:
+ StartCommand(Command *commandToStart);
+ virtual ~StartCommand() {}
+
+protected:
+ virtual void Initialize();
+ virtual void Execute();
+ virtual bool IsFinished();
+ virtual void End();
+ virtual void Interrupted();
+
+private:
+ Command *m_commandToFork;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Commands/Subsystem.cpp b/aos/externals/WPILib/WPILib/Commands/Subsystem.cpp
new file mode 100644
index 0000000..ed30f2f
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/Subsystem.cpp
@@ -0,0 +1,160 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/Subsystem.h"
+
+#include "Commands/Command.h"
+#include "Commands/Scheduler.h"
+#include "NetworkTables/NetworkTable.h"
+#include "WPIErrors.h"
+
+/**
+ * Creates a subsystem with the given name
+ * @param name the name of the subsystem
+ */
+Subsystem::Subsystem(const char *name) :
+ m_table(NULL),
+ m_currentCommand(NULL),
+ m_defaultCommand(NULL),
+ m_initializedDefaultCommand(false)
+{
+ m_name = name;
+ Scheduler::GetInstance()->RegisterSubsystem(this);
+}
+/**
+ * Initialize the default command for this subsystem
+ * This is meant to be the place to call SetDefaultCommand in a subsystem and will be called
+ * on all the subsystems by the CommandBase method before the program starts running by using
+ * the list of all registered Subsystems inside the Scheduler.
+ *
+ * This should be overridden by a Subsystem that has a default Command
+ */
+void Subsystem::InitDefaultCommand() {
+
+}
+
+/**
+ * Sets the default command. If this is not called or is called with null,
+ * then there will be no default command for the subsystem.
+ *
+ * <p><b>WARNING:</b> This should <b>NOT</b> be called in a constructor if the subsystem is a
+ * singleton.</p>
+ *
+ * @param command the default command (or null if there should be none)
+ */
+void Subsystem::SetDefaultCommand(Command *command)
+{
+ if (command == NULL)
+ {
+ m_defaultCommand = NULL;
+ }
+ else
+ {
+ bool found = false;
+ Command::SubsystemSet requirements = command->GetRequirements();
+ Command::SubsystemSet::iterator iter = requirements.begin();
+ for (; iter != requirements.end(); iter++)
+ {
+ if (*iter == this)
+ {
+ found = true;
+ break;
+ }
+ }
+
+ if (!found)
+ {
+ wpi_setWPIErrorWithContext(CommandIllegalUse, "A default command must require the subsystem");
+ return;
+ }
+
+ m_defaultCommand = command;
+ }
+ if (m_table != NULL)
+ {
+ if (m_defaultCommand != 0)
+ {
+ m_table->PutBoolean("hasDefault", true);
+ m_table->PutSubTable("default", m_defaultCommand->GetTable());
+ }
+ else
+ {
+ m_table->PutBoolean("hasDefault", false);
+ }
+ }
+}
+
+/**
+ * Returns the default command (or null if there is none).
+ * @return the default command
+ */
+Command *Subsystem::GetDefaultCommand()
+{
+ if (!m_initializedDefaultCommand) {
+ m_initializedDefaultCommand = true;
+ InitDefaultCommand();
+ }
+ return m_defaultCommand;
+}
+
+/**
+ * Sets the current command
+ * @param command the new current command
+ */
+void Subsystem::SetCurrentCommand(Command *command)
+{
+ m_currentCommand = command;
+}
+
+/**
+ * Returns the command which currently claims this subsystem.
+ * @return the command which currently claims this subsystem
+ */
+Command *Subsystem::GetCurrentCommand()
+{
+ return m_currentCommand;
+}
+
+/**
+ * Call this to alert Subsystem that the current command is actually the command.
+ * Sometimes, the {@link Subsystem} is told that it has no command while the {@link Scheduler}
+ * is going through the loop, only to be soon after given a new one. This will avoid that situation.
+ */
+void Subsystem::ConfirmCommand()
+{
+ if (m_table != NULL)
+ {
+ if (m_currentCommand != NULL)
+ {
+ m_table->PutBoolean("hasCommand", true);
+ m_table->PutSubTable("command", m_currentCommand->GetTable());
+ }
+ else
+ {
+ m_table->PutBoolean("hasCommand", false);
+ }
+ }
+}
+
+std::string Subsystem::GetName()
+{
+ return m_name;
+}
+
+std::string Subsystem::GetType()
+{
+ return "Subsystem";
+}
+
+NetworkTable *Subsystem::GetTable()
+{
+ if (m_table == NULL)
+ {
+ m_table = new NetworkTable();
+ m_table->PutInt("count", 0);
+ }
+ return m_table;
+}
diff --git a/aos/externals/WPILib/WPILib/Commands/Subsystem.h b/aos/externals/WPILib/WPILib/Commands/Subsystem.h
new file mode 100644
index 0000000..8f1e529
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/Subsystem.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SUBSYSTEM_H__
+#define __SUBSYSTEM_H__
+
+#include "ErrorBase.h"
+#include "SmartDashboard/SmartDashboardNamedData.h"
+#include <string>
+
+class NetworkTable;
+class Command;
+
+class Subsystem : public SmartDashboardNamedData, public ErrorBase
+{
+ friend class Scheduler;
+public:
+ Subsystem(const char *name);
+ virtual ~Subsystem() {}
+
+ virtual std::string GetName();
+ virtual std::string GetType();
+ virtual NetworkTable *GetTable();
+
+ void SetDefaultCommand(Command *command);
+ Command *GetDefaultCommand();
+ void SetCurrentCommand(Command *command);
+ Command *GetCurrentCommand();
+ virtual void InitDefaultCommand();
+
+private:
+ void ConfirmCommand();
+
+ NetworkTable *m_table;
+ Command *m_currentCommand;
+ Command *m_defaultCommand;
+ std::string m_name;
+ bool m_initializedDefaultCommand;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Commands/WaitCommand.cpp b/aos/externals/WPILib/WPILib/Commands/WaitCommand.cpp
new file mode 100644
index 0000000..508db04
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/WaitCommand.cpp
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/WaitCommand.h"
+#include <sstream>
+
+WaitCommand::WaitCommand(double timeout) :
+ Command(((std::stringstream&)(std::stringstream("Wait(") << timeout << ")")).str().c_str(), timeout)
+{
+}
+
+WaitCommand::WaitCommand(const char *name, double timeout) :
+ Command(name, timeout)
+{
+}
+
+void WaitCommand::Initialize()
+{
+}
+
+void WaitCommand::Execute()
+{
+}
+
+bool WaitCommand::IsFinished()
+{
+ return IsTimedOut();
+}
+
+void WaitCommand::End()
+{
+}
+
+void WaitCommand::Interrupted()
+{
+}
diff --git a/aos/externals/WPILib/WPILib/Commands/WaitCommand.h b/aos/externals/WPILib/WPILib/Commands/WaitCommand.h
new file mode 100644
index 0000000..036bae8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/WaitCommand.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __WAIT_COMMAND_H__
+#define __WAIT_COMMAND_H__
+
+#include "Commands/Command.h"
+
+class WaitCommand : public Command
+{
+public:
+ WaitCommand(double timeout);
+ WaitCommand(const char *name, double timeout);
+ virtual ~WaitCommand() {}
+
+protected:
+ virtual void Initialize();
+ virtual void Execute();
+ virtual bool IsFinished();
+ virtual void End();
+ virtual void Interrupted();
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Commands/WaitForChildren.cpp b/aos/externals/WPILib/WPILib/Commands/WaitForChildren.cpp
new file mode 100644
index 0000000..e168513
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/WaitForChildren.cpp
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/WaitForChildren.h"
+#include "Commands/CommandGroup.h"
+
+WaitForChildren::WaitForChildren(double timeout) :
+ Command("WaitForChildren", timeout)
+{
+}
+
+WaitForChildren::WaitForChildren(const char *name, double timeout) :
+ Command(name, timeout)
+{
+}
+
+void WaitForChildren::Initialize()
+{
+}
+
+void WaitForChildren::Execute()
+{
+}
+
+void WaitForChildren::End()
+{
+}
+
+void WaitForChildren::Interrupted()
+{
+}
+
+bool WaitForChildren::IsFinished()
+{
+ return GetGroup() == NULL || GetGroup()->GetSize() == 0;
+}
diff --git a/aos/externals/WPILib/WPILib/Commands/WaitForChildren.h b/aos/externals/WPILib/WPILib/Commands/WaitForChildren.h
new file mode 100644
index 0000000..2f4e3ea
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/WaitForChildren.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __WAIT_FOR_CHILDREN_H__
+#define __WAIT_FOR_CHILDREN_H__
+
+#include "Commands/Command.h"
+
+class WaitForChildren : public Command
+{
+public:
+ WaitForChildren(double timeout);
+ WaitForChildren(const char *name, double timeout);
+ virtual ~WaitForChildren() {}
+
+protected:
+ virtual void Initialize();
+ virtual void Execute();
+ virtual bool IsFinished();
+ virtual void End();
+ virtual void Interrupted();
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Commands/WaitUntilCommand.cpp b/aos/externals/WPILib/WPILib/Commands/WaitUntilCommand.cpp
new file mode 100644
index 0000000..3d521b8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/WaitUntilCommand.cpp
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Commands/WaitUntilCommand.h"
+#include "DriverStation.h"
+#include "Timer.h"
+
+/**
+ * A {@link WaitCommand} will wait until a certain match time before finishing.
+ * This will wait until the game clock reaches some value, then continue to the
+ * next command.
+ * @see CommandGroup
+ */
+WaitUntilCommand::WaitUntilCommand(double time) :
+ Command("WaitUntilCommand", time)
+{
+ m_time = time;
+}
+
+WaitUntilCommand::WaitUntilCommand(const char *name, double time) :
+ Command(name, time)
+{
+ m_time = time;
+}
+
+void WaitUntilCommand::Initialize()
+{
+}
+
+void WaitUntilCommand::Execute()
+{
+}
+
+/**
+ * Check if we've reached the actual finish time.
+ */
+bool WaitUntilCommand::IsFinished()
+{
+ return DriverStation::GetInstance()->GetMatchTime() >= m_time;
+}
+
+void WaitUntilCommand::End()
+{
+}
+
+void WaitUntilCommand::Interrupted()
+{
+}
diff --git a/aos/externals/WPILib/WPILib/Commands/WaitUntilCommand.h b/aos/externals/WPILib/WPILib/Commands/WaitUntilCommand.h
new file mode 100644
index 0000000..b816ccf
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Commands/WaitUntilCommand.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __WAIT_UNTIL_COMMAND_H__
+#define __WAIT_UNTIL_COMMAND_H__
+
+#include "Commands/Command.h"
+
+class WaitUntilCommand : public Command
+{
+public:
+ WaitUntilCommand(double time);
+ WaitUntilCommand(const char *name, double time);
+ virtual ~WaitUntilCommand() {}
+
+protected:
+ virtual void Initialize();
+ virtual void Execute();
+ virtual bool IsFinished();
+ virtual void End();
+ virtual void Interrupted();
+
+private:
+ double m_time;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Compressor.cpp b/aos/externals/WPILib/WPILib/Compressor.cpp
new file mode 100644
index 0000000..6a595b8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Compressor.cpp
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Compressor.h"
+#include "DigitalInput.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+
+/**
+ * Internal task.
+ *
+ * Task which checks the compressor pressure switch and operates the relay as necessary
+ * depending on the pressure.
+ *
+ * Do not call this function directly.
+ */
+static void CompressorChecker(Compressor *c)
+{
+ while (1)
+ {
+ if (c->Enabled())
+ {
+ c->SetRelayValue( c->GetPressureSwitchValue() == 0 ? Relay::kOn : Relay::kOff );
+ }
+ else
+ {
+ c->SetRelayValue(Relay::kOff);
+ }
+ Wait(0.5);
+ }
+}
+
+/**
+ * Initialize the Compressor object.
+ * This method is the common initialization code for all the constructors for the Compressor
+ * object. It takes the relay channel and pressure switch channel and spawns a task that polls the
+ * compressor and sensor.
+ *
+ * You MUST start the compressor by calling the Start() method.
+ */
+void Compressor::InitCompressor(UINT8 pressureSwitchModuleNumber,
+ UINT32 pressureSwitchChannel,
+ UINT8 compresssorRelayModuleNumber,
+ UINT32 compressorRelayChannel)
+{
+ m_enabled = false;
+ m_pressureSwitch = new DigitalInput(pressureSwitchModuleNumber, pressureSwitchChannel);
+ m_relay = new Relay(compresssorRelayModuleNumber, compressorRelayChannel, Relay::kForwardOnly);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Compressor, 0);
+
+ if (!m_task.Start((INT32)this))
+ {
+ wpi_setWPIError(CompressorTaskError);
+ }
+}
+
+/**
+ * Compressor constructor.
+ * Given a fully specified relay channel and pressure switch channel, initialize the Compressor object.
+ *
+ * You MUST start the compressor by calling the Start() method.
+ *
+ * @param pressureSwitchModuleNumber The digital module that the pressure switch is attached to.
+ * @param pressureSwitchChannel The GPIO channel that the pressure switch is attached to.
+ * @param compresssorRelayModuleNumber The digital module that the compressor relay is attached to.
+ * @param compressorRelayChannel The relay channel that the compressor relay is attached to.
+ */
+Compressor::Compressor(UINT8 pressureSwitchModuleNumber,
+ UINT32 pressureSwitchChannel,
+ UINT8 compresssorRelayModuleNumber,
+ UINT32 compressorRelayChannel)
+ : m_task ("Compressor", (FUNCPTR)CompressorChecker)
+{
+ InitCompressor(pressureSwitchModuleNumber,
+ pressureSwitchChannel,
+ compresssorRelayModuleNumber,
+ compressorRelayChannel);
+}
+
+/**
+ * Compressor constructor.
+ * Given a relay channel and pressure switch channel (both in the default digital module), initialize
+ * the Compressor object.
+ *
+ * You MUST start the compressor by calling the Start() method.
+ *
+ * @param pressureSwitchChannel The GPIO channel that the pressure switch is attached to.
+ * @param compressorRelayChannel The relay channel that the compressor relay is attached to.
+ */
+Compressor::Compressor(UINT32 pressureSwitchChannel, UINT32 compressorRelayChannel)
+ : m_task ("Compressor", (FUNCPTR)CompressorChecker)
+{
+ InitCompressor(GetDefaultDigitalModule(),
+ pressureSwitchChannel,
+ GetDefaultDigitalModule(),
+ compressorRelayChannel);
+}
+
+/**
+ * Delete the Compressor object.
+ * Delete the allocated resources for the compressor and kill the compressor task that is polling
+ * the pressure switch.
+ */
+Compressor::~Compressor()
+{
+ delete m_pressureSwitch;
+ delete m_relay;
+}
+
+/**
+ * Operate the relay for the compressor.
+ * Change the value of the relay output that is connected to the compressor motor.
+ * This is only intended to be called by the internal polling thread.
+ */
+void Compressor::SetRelayValue(Relay::Value relayValue)
+{
+ m_relay->Set(relayValue);
+}
+
+/**
+ * Get the pressure switch value.
+ * Read the pressure switch digital input.
+ *
+ * @return The current state of the pressure switch.
+ */
+UINT32 Compressor::GetPressureSwitchValue()
+{
+ return m_pressureSwitch->Get();
+}
+
+/**
+ * Start the compressor.
+ * This method will allow the polling loop to actually operate the compressor. The
+ * is stopped by default and won't operate until starting it.
+ */
+void Compressor::Start()
+{
+ m_enabled = true;
+}
+
+/**
+ * Stop the compressor.
+ * This method will stop the compressor from turning on.
+ */
+void Compressor::Stop()
+{
+ m_enabled = false;
+}
+
+/**
+ * Get the state of the enabled flag.
+ * Return the state of the enabled flag for the compressor and pressure switch
+ * combination.
+ *
+ * @return The state of the compressor thread's enable flag.
+ */
+bool Compressor::Enabled()
+{
+ return m_enabled;
+}
+
diff --git a/aos/externals/WPILib/WPILib/Compressor.h b/aos/externals/WPILib/WPILib/Compressor.h
new file mode 100644
index 0000000..57fe252
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Compressor.h
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef COMPRESSOR_H_
+#define COMPRESSOR_H_
+
+#define COMPRESSOR_PRIORITY 90
+
+#include "SensorBase.h"
+#include "Relay.h"
+#include "Task.h"
+
+class DigitalInput;
+
+/**
+ * Compressor object.
+ * The Compressor object is designed to handle the operation of the compressor, pressure sensor and
+ * relay for a FIRST robot pneumatics system. The Compressor object starts a task which runs in the
+ * backround and periodically polls the pressure sensor and operates the relay that controls the
+ * compressor.
+ */
+class Compressor: public SensorBase
+{
+public:
+ Compressor(UINT32 pressureSwitchChannel, UINT32 compressorRelayChannel);
+ Compressor(UINT8 pressureSwitchModuleNumber, UINT32 pressureSwitchChannel,
+ UINT8 compresssorRelayModuleNumber, UINT32 compressorRelayChannel);
+ ~Compressor();
+
+ void Start();
+ void Stop();
+ bool Enabled();
+ UINT32 GetPressureSwitchValue();
+ void SetRelayValue(Relay::Value relayValue);
+
+private:
+ void InitCompressor(UINT8 pressureSwitchModuleNumber, UINT32 pressureSwitchChannel,
+ UINT8 compresssorRelayModuleNumber, UINT32 compressorRelayChannel);
+
+ DigitalInput *m_pressureSwitch;
+ Relay *m_relay;
+ bool m_enabled;
+ Task m_task;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Counter.cpp b/aos/externals/WPILib/WPILib/Counter.cpp
new file mode 100644
index 0000000..ead4d1e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Counter.cpp
@@ -0,0 +1,667 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Counter.h"
+#include "AnalogTrigger.h"
+#include "DigitalInput.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+static Resource *counters = NULL;
+
+/**
+ * Create an instance of a counter object.
+ * This creates a ChipObject counter and initializes status variables appropriately
+ */
+void Counter::InitCounter(Mode mode)
+{
+ Resource::CreateResourceObject(&counters, tCounter::kNumSystems);
+ UINT32 index = counters->Allocate("Counter");
+ if (index == ~0ul)
+ {
+ CloneError(counters);
+ return;
+ }
+ m_index = index;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter = tCounter::create(m_index, &localStatus);
+ m_counter->writeConfig_Mode(mode, &localStatus);
+ m_upSource = NULL;
+ m_downSource = NULL;
+ m_allocatedUpSource = false;
+ m_allocatedDownSource = false;
+ m_counter->writeTimerConfig_AverageSize(1, &localStatus);
+ wpi_setError(localStatus);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Counter, index, mode);
+}
+
+/**
+ * Create an instance of a counter where no sources are selected.
+ * Then they all must be selected by calling functions to specify the upsource and the downsource
+ * independently.
+ */
+Counter::Counter() :
+ m_upSource(NULL),
+ m_downSource(NULL),
+ m_counter(NULL)
+{
+ InitCounter();
+}
+
+/**
+ * Create an instance of a counter from a Digital Input.
+ * This is used if an existing digital input is to be shared by multiple other objects such
+ * as encoders.
+ */
+Counter::Counter(DigitalSource *source) :
+ m_upSource(NULL),
+ m_downSource(NULL),
+ m_counter(NULL)
+{
+ InitCounter();
+ SetUpSource(source);
+ ClearDownSource();
+}
+
+Counter::Counter(DigitalSource &source) :
+ m_upSource(NULL),
+ m_downSource(NULL),
+ m_counter(NULL)
+{
+ InitCounter();
+ SetUpSource(&source);
+ ClearDownSource();
+}
+
+/**
+ * Create an instance of a Counter object.
+ * Create an up-Counter instance given a channel. The default digital module is assumed.
+ */
+Counter::Counter(UINT32 channel) :
+ m_upSource(NULL),
+ m_downSource(NULL),
+ m_counter(NULL)
+{
+ InitCounter();
+ SetUpSource(channel);
+ ClearDownSource();
+}
+
+/**
+ * Create an instance of a Counter object.
+ * Create an instance of an up-Counter given a digital module and a channel.
+ * @param moduleNumber The digital module (1 or 2).
+ * @param channel The channel in the digital module
+ */
+Counter::Counter(UINT8 moduleNumber, UINT32 channel) :
+ m_upSource(NULL),
+ m_downSource(NULL),
+ m_counter(NULL)
+{
+ InitCounter();
+ SetUpSource(moduleNumber, channel);
+ ClearDownSource();
+}
+
+/**
+ * Create an instance of a Counter object.
+ * Create an instance of a simple up-Counter given an analog trigger.
+ * Use the trigger state output from the analog trigger.
+ */
+Counter::Counter(AnalogTrigger *trigger) :
+ m_upSource(NULL),
+ m_downSource(NULL),
+ m_counter(NULL)
+{
+ InitCounter();
+ SetUpSource(trigger->CreateOutput(AnalogTriggerOutput::kState));
+ ClearDownSource();
+ m_allocatedUpSource = true;
+}
+
+Counter::Counter(AnalogTrigger &trigger) :
+ m_upSource(NULL),
+ m_downSource(NULL),
+ m_counter(NULL)
+{
+ InitCounter();
+ SetUpSource(trigger.CreateOutput(AnalogTriggerOutput::kState));
+ ClearDownSource();
+ m_allocatedUpSource = true;
+}
+
+Counter::Counter(EncodingType encodingType, DigitalSource *upSource, DigitalSource *downSource, bool inverted) :
+ m_upSource(NULL),
+ m_downSource(NULL),
+ m_counter(NULL)
+{
+ if (encodingType != k1X && encodingType != k2X)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "Counter only supports 1X and 2X quadrature decoding.");
+ return;
+ }
+ InitCounter(kExternalDirection);
+ SetUpSource(upSource);
+ SetDownSource(downSource);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+
+ if (encodingType == k1X)
+ {
+ SetUpSourceEdge(true, false);
+ m_counter->writeTimerConfig_AverageSize(1, &localStatus);
+ }
+ else
+ {
+ SetUpSourceEdge(true, true);
+ m_counter->writeTimerConfig_AverageSize(2, &localStatus);
+ }
+
+ wpi_setError(localStatus);
+ SetDownSourceEdge(inverted, true);
+}
+
+/**
+ * Delete the Counter object.
+ */
+Counter::~Counter()
+{
+ SetUpdateWhenEmpty(true);
+ if (m_allocatedUpSource)
+ {
+ delete m_upSource;
+ m_upSource = NULL;
+ }
+ if (m_allocatedDownSource)
+ {
+ delete m_downSource;
+ m_downSource = NULL;
+ }
+ delete m_counter;
+ m_counter = NULL;
+ counters->Free(m_index);
+}
+
+/**
+ * Set the up source for the counter as digital input channel and slot.
+ *
+ * @param moduleNumber The digital module (1 or 2).
+ * @param channel The digital channel (1..14).
+ */
+void Counter::SetUpSource(UINT8 moduleNumber, UINT32 channel)
+{
+ if (StatusIsFatal()) return;
+ SetUpSource(new DigitalInput(moduleNumber, channel));
+ m_allocatedUpSource = true;
+}
+
+/**
+ * Set the upsource for the counter as a digital input channel.
+ * The slot will be the default digital module slot.
+ */
+void Counter::SetUpSource(UINT32 channel)
+{
+ if (StatusIsFatal()) return;
+ SetUpSource(GetDefaultDigitalModule(), channel);
+ m_allocatedUpSource = true;
+}
+
+/**
+ * Set the up counting source to be an analog trigger.
+ * @param analogTrigger The analog trigger object that is used for the Up Source
+ * @param triggerType The analog trigger output that will trigger the counter.
+ */
+void Counter::SetUpSource(AnalogTrigger *analogTrigger, AnalogTriggerOutput::Type triggerType)
+{
+ if (StatusIsFatal()) return;
+ SetUpSource(analogTrigger->CreateOutput(triggerType));
+ m_allocatedUpSource = true;
+}
+
+/**
+ * Set the up counting source to be an analog trigger.
+ * @param analogTrigger The analog trigger object that is used for the Up Source
+ * @param triggerType The analog trigger output that will trigger the counter.
+ */
+void Counter::SetUpSource(AnalogTrigger &analogTrigger, AnalogTriggerOutput::Type triggerType)
+{
+ SetUpSource(&analogTrigger, triggerType);
+}
+
+/**
+ * Set the source object that causes the counter to count up.
+ * Set the up counting DigitalSource.
+ */
+void Counter::SetUpSource(DigitalSource *source)
+{
+ if (StatusIsFatal()) return;
+ if (m_allocatedUpSource)
+ {
+ delete m_upSource;
+ m_upSource = NULL;
+ m_allocatedUpSource = false;
+ }
+ m_upSource = source;
+ if (m_upSource->StatusIsFatal())
+ {
+ CloneError(m_upSource);
+ }
+ else
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->writeConfig_UpSource_Module(source->GetModuleForRouting(), &localStatus);
+ m_counter->writeConfig_UpSource_Channel(source->GetChannelForRouting(), &localStatus);
+ m_counter->writeConfig_UpSource_AnalogTrigger(source->GetAnalogTriggerForRouting(), &localStatus);
+
+ if(m_counter->readConfig_Mode(&localStatus) == kTwoPulse ||
+ m_counter->readConfig_Mode(&localStatus) == kExternalDirection)
+ {
+ SetUpSourceEdge(true, false);
+ }
+ m_counter->strobeReset(&localStatus);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Set the source object that causes the counter to count up.
+ * Set the up counting DigitalSource.
+ */
+void Counter::SetUpSource(DigitalSource &source)
+{
+ SetUpSource(&source);
+}
+
+/**
+ * Set the edge sensitivity on an up counting source.
+ * Set the up source to either detect rising edges or falling edges.
+ */
+void Counter::SetUpSourceEdge(bool risingEdge, bool fallingEdge)
+{
+ if (StatusIsFatal()) return;
+ if (m_upSource == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "Must set non-NULL UpSource before setting UpSourceEdge");
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->writeConfig_UpRisingEdge(risingEdge, &localStatus);
+ m_counter->writeConfig_UpFallingEdge(fallingEdge, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Disable the up counting source to the counter.
+ */
+void Counter::ClearUpSource()
+{
+ if (StatusIsFatal()) return;
+ if (m_allocatedUpSource)
+ {
+ delete m_upSource;
+ m_upSource = NULL;
+ m_allocatedUpSource = false;
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool state = m_counter->readConfig_Enable(&localStatus);
+ m_counter->writeConfig_Enable(false, &localStatus);
+ m_counter->writeConfig_UpFallingEdge(false, &localStatus);
+ m_counter->writeConfig_UpRisingEdge(false, &localStatus);
+ // Index 0 of digital is always 0.
+ m_counter->writeConfig_UpSource_Channel(0, &localStatus);
+ m_counter->writeConfig_UpSource_AnalogTrigger(false, &localStatus);
+ m_counter->writeConfig_Enable(state, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Set the down counting source to be a digital input channel.
+ * The slot will be set to the default digital module slot.
+ */
+void Counter::SetDownSource(UINT32 channel)
+{
+ if (StatusIsFatal()) return;
+ SetDownSource(new DigitalInput(channel));
+ m_allocatedDownSource = true;
+}
+
+/**
+ * Set the down counting source to be a digital input slot and channel.
+ *
+ * @param moduleNumber The digital module (1 or 2).
+ * @param channel The digital channel (1..14).
+ */
+void Counter::SetDownSource(UINT8 moduleNumber, UINT32 channel)
+{
+ if (StatusIsFatal()) return;
+ SetDownSource(new DigitalInput(moduleNumber, channel));
+ m_allocatedDownSource = true;
+}
+
+/**
+ * Set the down counting source to be an analog trigger.
+ * @param analogTrigger The analog trigger object that is used for the Down Source
+ * @param triggerType The analog trigger output that will trigger the counter.
+ */
+void Counter::SetDownSource(AnalogTrigger *analogTrigger, AnalogTriggerOutput::Type triggerType)
+{
+ if (StatusIsFatal()) return;
+ SetDownSource(analogTrigger->CreateOutput(triggerType));
+ m_allocatedDownSource = true;
+}
+
+/**
+ * Set the down counting source to be an analog trigger.
+ * @param analogTrigger The analog trigger object that is used for the Down Source
+ * @param triggerType The analog trigger output that will trigger the counter.
+ */
+void Counter::SetDownSource(AnalogTrigger &analogTrigger, AnalogTriggerOutput::Type triggerType)
+{
+ SetDownSource(&analogTrigger, triggerType);
+}
+
+/**
+ * Set the source object that causes the counter to count down.
+ * Set the down counting DigitalSource.
+ */
+void Counter::SetDownSource(DigitalSource *source)
+{
+ if (StatusIsFatal()) return;
+ if (m_allocatedDownSource)
+ {
+ delete m_downSource;
+ m_downSource = NULL;
+ m_allocatedDownSource = false;
+ }
+ m_downSource = source;
+ if (m_downSource->StatusIsFatal())
+ {
+ CloneError(m_downSource);
+ }
+ else
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ unsigned char mode = m_counter->readConfig_Mode(&localStatus);
+ if (mode != kTwoPulse && mode != kExternalDirection)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "Counter only supports DownSource in TwoPulse and ExternalDirection modes.");
+ return;
+ }
+ m_counter->writeConfig_DownSource_Module(source->GetModuleForRouting(), &localStatus);
+ m_counter->writeConfig_DownSource_Channel(source->GetChannelForRouting(), &localStatus);
+ m_counter->writeConfig_DownSource_AnalogTrigger(source->GetAnalogTriggerForRouting(), &localStatus);
+
+ SetDownSourceEdge(true, false);
+ m_counter->strobeReset(&localStatus);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Set the source object that causes the counter to count down.
+ * Set the down counting DigitalSource.
+ */
+void Counter::SetDownSource(DigitalSource &source)
+{
+ SetDownSource(&source);
+}
+
+/**
+ * Set the edge sensitivity on a down counting source.
+ * Set the down source to either detect rising edges or falling edges.
+ */
+void Counter::SetDownSourceEdge(bool risingEdge, bool fallingEdge)
+{
+ if (StatusIsFatal()) return;
+ if (m_downSource == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "Must set non-NULL DownSource before setting DownSourceEdge");
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->writeConfig_DownRisingEdge(risingEdge, &localStatus);
+ m_counter->writeConfig_DownFallingEdge(fallingEdge, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Disable the down counting source to the counter.
+ */
+void Counter::ClearDownSource()
+{
+ if (StatusIsFatal()) return;
+ if (m_allocatedDownSource)
+ {
+ delete m_downSource;
+ m_downSource = NULL;
+ m_allocatedDownSource = false;
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool state = m_counter->readConfig_Enable(&localStatus);
+ m_counter->writeConfig_Enable(false, &localStatus);
+ m_counter->writeConfig_DownFallingEdge(false, &localStatus);
+ m_counter->writeConfig_DownRisingEdge(false, &localStatus);
+ // Index 0 of digital is always 0.
+ m_counter->writeConfig_DownSource_Channel(0, &localStatus);
+ m_counter->writeConfig_DownSource_AnalogTrigger(false, &localStatus);
+ m_counter->writeConfig_Enable(state, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Set standard up / down counting mode on this counter.
+ * Up and down counts are sourced independently from two inputs.
+ */
+void Counter::SetUpDownCounterMode()
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->writeConfig_Mode(kTwoPulse, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Set external direction mode on this counter.
+ * Counts are sourced on the Up counter input.
+ * The Down counter input represents the direction to count.
+ */
+void Counter::SetExternalDirectionMode()
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->writeConfig_Mode(kExternalDirection, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Set Semi-period mode on this counter.
+ * Counts up on both rising and falling edges.
+ */
+void Counter::SetSemiPeriodMode(bool highSemiPeriod)
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->writeConfig_Mode(kSemiperiod, &localStatus);
+ m_counter->writeConfig_UpRisingEdge(highSemiPeriod, &localStatus);
+ SetUpdateWhenEmpty(false);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Configure the counter to count in up or down based on the length of the input pulse.
+ * This mode is most useful for direction sensitive gear tooth sensors.
+ * @param threshold The pulse length beyond which the counter counts the opposite direction. Units are seconds.
+ */
+void Counter::SetPulseLengthMode(float threshold)
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->writeConfig_Mode(kPulseLength, &localStatus);
+ m_counter->writeConfig_PulseLengthThreshold((UINT32)(threshold * 1.0e6) * kSystemClockTicksPerMicrosecond, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Start the Counter counting.
+ * This enables the counter and it starts accumulating counts from the associated
+ * input channel. The counter value is not reset on starting, and still has the previous value.
+ */
+void Counter::Start()
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->writeConfig_Enable(1, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Read the current counter value.
+ * Read the value at this instant. It may still be running, so it reflects the current value. Next
+ * time it is read, it might have a different value.
+ */
+INT32 Counter::Get()
+{
+ if (StatusIsFatal()) return 0;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ INT32 value = m_counter->readOutput_Value(&localStatus);
+ wpi_setError(localStatus);
+ return value;
+}
+
+/**
+ * Reset the Counter to zero.
+ * Set the counter value to zero. This doesn't effect the running state of the counter, just sets
+ * the current value to zero.
+ */
+void Counter::Reset()
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->strobeReset(&localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Stop the Counter.
+ * Stops the counting but doesn't effect the current value.
+ */
+void Counter::Stop()
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->writeConfig_Enable(0, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/*
+ * Get the Period of the most recent count.
+ * Returns the time interval of the most recent count. This can be used for velocity calculations
+ * to determine shaft speed.
+ * @returns The period of the last two pulses in units of seconds.
+ */
+double Counter::GetPeriod()
+{
+ if (StatusIsFatal()) return 0.0;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ tCounter::tTimerOutput output = m_counter->readTimerOutput(&localStatus);
+ double period;
+ if (output.Stalled)
+ {
+ // Return infinity
+ double zero = 0.0;
+ period = 1.0 / zero;
+ }
+ else
+ {
+ // output.Period is a fixed point number that counts by 2 (24 bits, 25 integer bits)
+ period = (double)(output.Period << 1) / (double)output.Count;
+ }
+ wpi_setError(localStatus);
+ return period * 1.0e-6;
+}
+
+/**
+ * Set the maximum period where the device is still considered "moving".
+ * Sets the maximum period where the device is considered moving. This value is used to determine
+ * the "stopped" state of the counter using the GetStopped method.
+ * @param maxPeriod The maximum period where the counted device is considered moving in
+ * seconds.
+ */
+void Counter::SetMaxPeriod(double maxPeriod)
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->writeTimerConfig_StallPeriod((UINT32)(maxPeriod * 1.0e6), &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Select whether you want to continue updating the event timer output when there are no samples captured.
+ * The output of the event timer has a buffer of periods that are averaged and posted to
+ * a register on the FPGA. When the timer detects that the event source has stopped
+ * (based on the MaxPeriod) the buffer of samples to be averaged is emptied. If you
+ * enable the update when empty, you will be notified of the stopped source and the event
+ * time will report 0 samples. If you disable update when empty, the most recent average
+ * will remain on the output until a new sample is acquired. You will never see 0 samples
+ * output (except when there have been no events since an FPGA reset) and you will likely not
+ * see the stopped bit become true (since it is updated at the end of an average and there are
+ * no samples to average).
+ */
+void Counter::SetUpdateWhenEmpty(bool enabled)
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_counter->writeTimerConfig_UpdateWhenEmpty(enabled, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Determine if the clock is stopped.
+ * Determine if the clocked input is stopped based on the MaxPeriod value set using the
+ * SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the device (and counter) are
+ * assumed to be stopped and it returns true.
+ * @return Returns true if the most recent counter period exceeds the MaxPeriod value set by
+ * SetMaxPeriod.
+ */
+bool Counter::GetStopped()
+{
+ if (StatusIsFatal()) return false;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ return m_counter->readTimerOutput_Stalled(&localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * The last direction the counter value changed.
+ * @return The last direction the counter value changed.
+ */
+bool Counter::GetDirection()
+{
+ if (StatusIsFatal()) return false;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool value = m_counter->readOutput_Direction(&localStatus);
+ wpi_setError(localStatus);
+ return value;
+}
+
+/**
+ * Set the Counter to return reversed sensing on the direction.
+ * This allows counters to change the direction they are counting in the case of 1X and 2X
+ * quadrature encoding only. Any other counter mode isn't supported.
+ * @param reverseDirection true if the value counted should be negated.
+ */
+void Counter::SetReverseDirection(bool reverseDirection)
+{
+ if (StatusIsFatal()) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ if (m_counter->readConfig_Mode(&localStatus) == kExternalDirection)
+ {
+ if (reverseDirection)
+ SetDownSourceEdge(true, true);
+ else
+ SetDownSourceEdge(false, true);
+ }
+ wpi_setError(localStatus);
+}
diff --git a/aos/externals/WPILib/WPILib/Counter.h b/aos/externals/WPILib/WPILib/Counter.h
new file mode 100644
index 0000000..0d3c125
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Counter.h
@@ -0,0 +1,82 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CPPCOUNTER_H_
+#define CPPCOUNTER_H_
+
+#include "AnalogTriggerOutput.h"
+#include "CounterBase.h"
+#include "SensorBase.h"
+
+/**
+ * Class for counting the number of ticks on a digital input channel.
+ * This is a general purpose class for counting repetitive events. It can return the number
+ * of counts, the period of the most recent cycle, and detect when the signal being counted
+ * has stopped by supplying a maximum cycle time.
+ */
+class Counter : public SensorBase, public CounterBase
+{
+public:
+ typedef enum {kTwoPulse=0, kSemiperiod=1, kPulseLength=2, kExternalDirection=3} Mode;
+
+ Counter();
+ explicit Counter(UINT32 channel);
+ Counter(UINT8 moduleNumber, UINT32 channel);
+ explicit Counter(DigitalSource *source);
+ explicit Counter(DigitalSource &source);
+ explicit Counter(AnalogTrigger *trigger);
+ explicit Counter(AnalogTrigger &trigger);
+ Counter(EncodingType encodingType, DigitalSource *upSource, DigitalSource *downSource, bool inverted);
+ virtual ~Counter();
+
+ void SetUpSource(UINT32 channel);
+ void SetUpSource(UINT8 moduleNumber, UINT32 channel);
+ void SetUpSource(AnalogTrigger *analogTrigger, AnalogTriggerOutput::Type triggerType);
+ void SetUpSource(AnalogTrigger &analogTrigger, AnalogTriggerOutput::Type triggerType);
+ void SetUpSource(DigitalSource *source);
+ void SetUpSource(DigitalSource &source);
+ void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
+ void ClearUpSource();
+
+ void SetDownSource(UINT32 channel);
+ void SetDownSource(UINT8 moduleNumber, UINT32 channel);
+ void SetDownSource(AnalogTrigger *analogTrigger, AnalogTriggerOutput::Type triggerType);
+ void SetDownSource(AnalogTrigger &analogTrigger, AnalogTriggerOutput::Type triggerType);
+ void SetDownSource(DigitalSource *source);
+ void SetDownSource(DigitalSource &source);
+ void SetDownSourceEdge(bool risingEdge, bool fallingEdge);
+ void ClearDownSource();
+
+ void SetUpDownCounterMode();
+ void SetExternalDirectionMode();
+ void SetSemiPeriodMode(bool highSemiPeriod);
+ void SetPulseLengthMode(float threshold);
+
+ void SetReverseDirection(bool reverseDirection);
+
+ // CounterBase interface
+ void Start();
+ INT32 Get();
+ void Reset();
+ void Stop();
+ double GetPeriod();
+ void SetMaxPeriod(double maxPeriod);
+ void SetUpdateWhenEmpty(bool enabled);
+ bool GetStopped();
+ bool GetDirection();
+ UINT32 GetIndex() {return m_index;}
+private:
+ void InitCounter(Mode mode = kTwoPulse);
+
+ DigitalSource *m_upSource; ///< What makes the counter count up.
+ DigitalSource *m_downSource; ///< What makes the counter count down.
+ bool m_allocatedUpSource; ///< Was the upSource allocated locally?
+ bool m_allocatedDownSource; ///< Was the downSource allocated locally?
+ tCounter *m_counter; ///< The FPGA counter object.
+ UINT32 m_index; ///< The index of this counter.
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/CounterBase.h b/aos/externals/WPILib/WPILib/CounterBase.h
new file mode 100644
index 0000000..69bf026
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/CounterBase.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CPPCOUNTER_BASE_H_
+#define CPPCOUNTER_BASE_H_
+
+/**
+ * Interface for counting the number of ticks on a digital input channel.
+ * Encoders, Gear tooth sensors, and counters should all subclass this so it can be used to
+ * build more advanced classes for control and driving.
+ */
+class CounterBase
+{
+public:
+ typedef enum {k1X, k2X, k4X} EncodingType;
+
+ virtual ~CounterBase() {}
+ virtual void Start() = 0;
+ virtual INT32 Get() = 0;
+ virtual void Reset() = 0;
+ virtual void Stop() = 0;
+ virtual double GetPeriod() = 0;
+ virtual void SetMaxPeriod(double maxPeriod) = 0;
+ virtual bool GetStopped() = 0;
+ virtual bool GetDirection() = 0;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Dashboard.cpp b/aos/externals/WPILib/WPILib/Dashboard.cpp
new file mode 100644
index 0000000..24e7e56
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Dashboard.cpp
@@ -0,0 +1,399 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Dashboard.h"
+#include "DriverStation.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Synchronized.h"
+#include "WPIErrors.h"
+#include <strLib.h>
+
+const INT32 Dashboard::kMaxDashboardDataSize;
+
+/**
+ * Dashboard contructor.
+ *
+ * This is only called once when the DriverStation constructor is called.
+ */
+Dashboard::Dashboard(SEM_ID statusDataSem)
+ : m_userStatusData (NULL)
+ , m_userStatusDataSize (0)
+ , m_localBuffer (NULL)
+ , m_localPrintBuffer (NULL)
+ , m_packPtr (NULL)
+ , m_printSemaphore (0)
+ , m_statusDataSemaphore (statusDataSem)
+{
+ m_userStatusData = new char[kMaxDashboardDataSize];
+ m_localBuffer = new char[kMaxDashboardDataSize];
+ m_localPrintBuffer = new char[kMaxDashboardDataSize * 2];
+ m_localPrintBuffer[0] = 0;
+ m_packPtr = m_localBuffer;
+ m_printSemaphore = semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+}
+
+/**
+ * Dashboard destructor.
+ *
+ * Called only when the DriverStation class is destroyed.
+ */
+Dashboard::~Dashboard()
+{
+ semDelete(m_printSemaphore);
+ m_packPtr = NULL;
+ delete [] m_localPrintBuffer;
+ m_localPrintBuffer = NULL;
+ delete [] m_localBuffer;
+ m_localBuffer = NULL;
+ delete [] m_userStatusData;
+ m_userStatusData = NULL;
+}
+
+/**
+ * Pack a signed 8-bit int into the dashboard data structure.
+ * @param value Data to be packed into the structure.
+ */
+void Dashboard::AddI8(INT8 value)
+{
+ if (!ValidateAdd(sizeof(INT8))) return;
+ memcpy(m_packPtr, (char*)&value, sizeof(value));
+ m_packPtr += sizeof(value);
+ AddedElement(kI8);
+}
+
+/**
+ * Pack a signed 16-bit int into the dashboard data structure.
+ * @param value Data to be packed into the structure.
+ */
+void Dashboard::AddI16(INT16 value)
+{
+ if (!ValidateAdd(sizeof(INT16))) return;
+ memcpy(m_packPtr, (char*)&value, sizeof(value));
+ m_packPtr += sizeof(value);
+ AddedElement(kI16);
+}
+
+/**
+ * Pack a signed 32-bit int into the dashboard data structure.
+ * @param value Data to be packed into the structure.
+ */
+void Dashboard::AddI32(INT32 value)
+{
+ if (!ValidateAdd(sizeof(INT32))) return;
+ memcpy(m_packPtr, (char*)&value, sizeof(value));
+ m_packPtr += sizeof(value);
+ AddedElement(kI32);
+}
+
+/**
+ * Pack an unsigned 8-bit int into the dashboard data structure.
+ * @param value Data to be packed into the structure.
+ */
+void Dashboard::AddU8(UINT8 value)
+{
+ if (!ValidateAdd(sizeof(UINT8))) return;
+ memcpy(m_packPtr, (char*)&value, sizeof(value));
+ m_packPtr += sizeof(value);
+ AddedElement(kU8);
+}
+
+/**
+ * Pack an unsigned 16-bit int into the dashboard data structure.
+ * @param value Data to be packed into the structure.
+ */
+void Dashboard::AddU16(UINT16 value)
+{
+ if (!ValidateAdd(sizeof(UINT16))) return;
+ memcpy(m_packPtr, (char*)&value, sizeof(value));
+ m_packPtr += sizeof(value);
+ AddedElement(kU16);
+}
+
+/**
+ * Pack an unsigned 32-bit int into the dashboard data structure.
+ * @param value Data to be packed into the structure.
+ */
+void Dashboard::AddU32(UINT32 value)
+{
+ if (!ValidateAdd(sizeof(UINT32))) return;
+ memcpy(m_packPtr, (char*)&value, sizeof(value));
+ m_packPtr += sizeof(value);
+ AddedElement(kU32);
+}
+
+/**
+ * Pack a 32-bit floating point number into the dashboard data structure.
+ * @param value Data to be packed into the structure.
+ */
+void Dashboard::AddFloat(float value)
+{
+ if (!ValidateAdd(sizeof(float))) return;
+ memcpy(m_packPtr, (char*)&value, sizeof(value));
+ m_packPtr += sizeof(value);
+ AddedElement(kFloat);
+}
+
+/**
+ * Pack a 64-bit floating point number into the dashboard data structure.
+ * @param value Data to be packed into the structure.
+ */
+void Dashboard::AddDouble(double value)
+{
+ if (!ValidateAdd(sizeof(double))) return;
+ memcpy(m_packPtr, (char*)&value, sizeof(value));
+ m_packPtr += sizeof(value);
+ AddedElement(kDouble);
+}
+
+/**
+ * Pack a boolean into the dashboard data structure.
+ * @param value Data to be packed into the structure.
+ */
+void Dashboard::AddBoolean(bool value)
+{
+ if (!ValidateAdd(sizeof(char))) return;
+ *m_packPtr = value ? 1 : 0;
+ m_packPtr += sizeof(char);
+ AddedElement(kBoolean);
+}
+
+/**
+ * Pack a NULL-terminated string of 8-bit characters into the dashboard data structure.
+ * @param value Data to be packed into the structure.
+ */
+void Dashboard::AddString(char* value)
+{
+ AddString(value, strlen(value));
+}
+
+/**
+ * Pack a string of 8-bit characters of specified length into the dashboard data structure.
+ * @param value Data to be packed into the structure.
+ * @param length The number of bytes in the string to pack.
+ */
+void Dashboard::AddString(char* value, INT32 length)
+{
+ if (!ValidateAdd(length + sizeof(length))) return;
+ memcpy(m_packPtr, (char*)&length, sizeof(length));
+ m_packPtr += sizeof(length);
+ memcpy(m_packPtr, (char*)&value, length);
+ m_packPtr += length;
+ AddedElement(kString);
+}
+
+/**
+ * Start an array in the packed dashboard data structure.
+ *
+ * After calling AddArray(), call the appropriate Add method for each element of the array.
+ * Make sure you call the same add each time. An array must contain elements of the same type.
+ * You can use clusters inside of arrays to make each element of the array contain a structure of values.
+ * You can also nest arrays inside of other arrays.
+ * Every call to AddArray() must have a matching call to FinalizeArray().
+ */
+void Dashboard::AddArray()
+{
+ if (!ValidateAdd(sizeof(INT32))) return;
+ m_complexTypeStack.push(kArray);
+ m_arrayElementCount.push_back(0);
+ m_arraySizePtr.push_back((INT32*)m_packPtr);
+ m_packPtr += sizeof(INT32);
+}
+
+/**
+ * Indicate the end of an array packed into the dashboard data structure.
+ *
+ * After packing data into the array, call FinalizeArray().
+ * Every call to AddArray() must have a matching call to FinalizeArray().
+ */
+void Dashboard::FinalizeArray()
+{
+ if (m_complexTypeStack.top() != kArray)
+ {
+ wpi_setWPIError(MismatchedComplexTypeClose);
+ return;
+ }
+ m_complexTypeStack.pop();
+ *(m_arraySizePtr.back()) = m_arrayElementCount.back();
+ m_arraySizePtr.pop_back();
+ if (m_arrayElementCount.back() != 0)
+ {
+ m_expectedArrayElementType.pop_back();
+ }
+ m_arrayElementCount.pop_back();
+ AddedElement(kOther);
+}
+
+/**
+ * Start a cluster in the packed dashboard data structure.
+ *
+ * After calling AddCluster(), call the appropriate Add method for each element of the cluster.
+ * You can use clusters inside of arrays to make each element of the array contain a structure of values.
+ * Every call to AddCluster() must have a matching call to FinalizeCluster().
+ */
+void Dashboard::AddCluster()
+{
+ m_complexTypeStack.push(kCluster);
+}
+
+/**
+ * Indicate the end of a cluster packed into the dashboard data structure.
+ *
+ * After packing data into the cluster, call FinalizeCluster().
+ * Every call to AddCluster() must have a matching call to FinalizeCluster().
+ */
+void Dashboard::FinalizeCluster()
+{
+ if (m_complexTypeStack.top() != kCluster)
+ {
+ wpi_setWPIError(MismatchedComplexTypeClose);
+ return;
+ }
+ m_complexTypeStack.pop();
+ AddedElement(kOther);
+}
+
+/**
+ * Print a string to the UserData text on the Dashboard.
+ *
+ * This will add text to the buffer to send to the dashboard.
+ * You must call Finalize() periodically to actually send the buffer to the dashboard if you are not using the packed dashboard data.
+ */
+void Dashboard::Printf(const char *writeFmt, ...)
+{
+ va_list args;
+ INT32 size;
+
+ // Check if the buffer has already been used for packing.
+ if (m_packPtr != m_localBuffer)
+ {
+ wpi_setWPIError(DashboardDataCollision);
+ return;
+ }
+ va_start (args, writeFmt);
+ {
+ Synchronized sync(m_printSemaphore);
+ vsprintf(m_localPrintBuffer + strlen(m_localPrintBuffer), writeFmt, args);
+ size = strlen(m_localPrintBuffer);
+ }
+ if (size > kMaxDashboardDataSize)
+ {
+ wpi_setWPIError(DashboardDataOverflow);
+ }
+
+ va_end (args);
+}
+
+/**
+ * Indicate that the packing is complete and commit the buffer to the DriverStation.
+ *
+ * The packing of the dashboard packet is complete.
+ * If you are not using the packed dashboard data, you can call Finalize() to commit the Printf() buffer and the error string buffer.
+ * In effect, you are packing an empty structure.
+ * Prepares a packet to go to the dashboard...
+ * @return The total size of the data packed into the userData field of the status packet.
+ */
+INT32 Dashboard::Finalize()
+{
+ if (!m_complexTypeStack.empty())
+ {
+ wpi_setWPIError(MismatchedComplexTypeClose);
+ return 0;
+ }
+
+ static bool reported = false;
+ if (!reported)
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_Dashboard, 0);
+ reported = true;
+ }
+
+ Synchronized sync(m_statusDataSemaphore);
+
+ // Sequence number
+ DriverStation::GetInstance()->IncrementUpdateNumber();
+
+ // Packed Dashboard Data
+ m_userStatusDataSize = m_packPtr - m_localBuffer;
+ memcpy(m_userStatusData, m_localBuffer, m_userStatusDataSize);
+ m_packPtr = m_localBuffer;
+
+ return m_userStatusDataSize;
+}
+
+/**
+ * Called by the DriverStation class to retrieve buffers, sizes, etc. for writing
+ * to the NetworkCommunication task.
+ * This function is called while holding the m_statusDataSemaphore.
+ */
+void Dashboard::GetStatusBuffer(char **userStatusData, INT32* userStatusDataSize)
+{
+ // User printed strings
+ if (m_localPrintBuffer[0] != 0)
+ {
+ // Sequence number
+ DriverStation::GetInstance()->IncrementUpdateNumber();
+
+ INT32 printSize;
+ Synchronized syncPrint(m_printSemaphore);
+ printSize = strlen(m_localPrintBuffer);
+ m_userStatusDataSize = printSize;
+ memcpy(m_userStatusData, m_localPrintBuffer, m_userStatusDataSize);
+ m_localPrintBuffer[0] = 0;
+ }
+
+ *userStatusData = m_userStatusData;
+ *userStatusDataSize = m_userStatusDataSize;
+}
+
+/**
+ * Validate that the data being packed will fit in the buffer.
+ */
+bool Dashboard::ValidateAdd(INT32 size)
+{
+ if ((m_packPtr - m_localBuffer) + size > kMaxDashboardDataSize)
+ {
+ wpi_setWPIError(DashboardDataOverflow);
+ return false;
+ }
+ // Make sure printf is not being used at the same time.
+ if (m_localPrintBuffer[0] != 0)
+ {
+ wpi_setWPIError(DashboardDataCollision);
+ return false;
+ }
+ return true;
+}
+
+/**
+ * Check for consistent types when adding elements to an array and keep track of the number of elements in the array.
+ */
+void Dashboard::AddedElement(Type type)
+{
+ if(IsArrayRoot())
+ {
+ if (m_arrayElementCount.back() == 0)
+ {
+ m_expectedArrayElementType.push_back(type);
+ }
+ else
+ {
+ if (type != m_expectedArrayElementType.back())
+ {
+ wpi_setWPIError(InconsistentArrayValueAdded);
+ }
+ }
+ m_arrayElementCount.back() = m_arrayElementCount.back() + 1;
+ }
+}
+
+/**
+ * If the top of the type stack an array?
+ */
+bool Dashboard::IsArrayRoot()
+{
+ return !m_complexTypeStack.empty() && m_complexTypeStack.top() == kArray;
+}
+
diff --git a/aos/externals/WPILib/WPILib/Dashboard.h b/aos/externals/WPILib/WPILib/Dashboard.h
new file mode 100644
index 0000000..dfcf989
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Dashboard.h
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __DASHBOARD_H__
+#define __DASHBOARD_H__
+
+#include "DashboardBase.h"
+#include "NetworkCommunication/FRCComm.h"
+#include <stack>
+#include <vector>
+#include <vxWorks.h>
+
+/**
+ * Pack data into the "user data" field that gets sent to the dashboard laptop
+ * via the driver station.
+ */
+class Dashboard : public DashboardBase
+{
+public:
+ explicit Dashboard(SEM_ID statusDataSemaphore);
+ virtual ~Dashboard();
+
+ enum Type {kI8, kI16, kI32, kU8, kU16, kU32, kFloat, kDouble, kBoolean, kString, kOther};
+ enum ComplexType {kArray, kCluster};
+
+ void AddI8(INT8 value);
+ void AddI16(INT16 value);
+ void AddI32(INT32 value);
+ void AddU8(UINT8 value);
+ void AddU16(UINT16 value);
+ void AddU32(UINT32 value);
+ void AddFloat(float value);
+ void AddDouble(double value);
+ void AddBoolean(bool value);
+ void AddString(char* value);
+ void AddString(char* value, INT32 length);
+
+ void AddArray();
+ void FinalizeArray();
+ void AddCluster();
+ void FinalizeCluster();
+
+ void Printf(const char *writeFmt, ...);
+
+ INT32 Finalize();
+ void GetStatusBuffer(char** userStatusData, INT32* userStatusDataSize);
+ void Flush() {}
+private:
+ static const INT32 kMaxDashboardDataSize = USER_STATUS_DATA_SIZE - sizeof(UINT32) * 3 - sizeof(UINT8); // 13 bytes needed for 3 size parameters and the sequence number
+
+ // Usage Guidelines...
+ DISALLOW_COPY_AND_ASSIGN(Dashboard);
+
+ bool ValidateAdd(INT32 size);
+ void AddedElement(Type type);
+ bool IsArrayRoot();
+
+ char *m_userStatusData;
+ INT32 m_userStatusDataSize;
+ char *m_localBuffer;
+ char *m_localPrintBuffer;
+ char *m_packPtr;
+ std::vector<Type> m_expectedArrayElementType;
+ std::vector<INT32> m_arrayElementCount;
+ std::vector<INT32*> m_arraySizePtr;
+ std::stack<ComplexType> m_complexTypeStack;
+ SEM_ID m_printSemaphore;
+ SEM_ID m_statusDataSemaphore;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/DashboardBase.h b/aos/externals/WPILib/WPILib/DashboardBase.h
new file mode 100644
index 0000000..2bc15d8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DashboardBase.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __DASHBOARDBASE_H__
+#define __DASHBOARDBASE_H__
+
+#include <vxWorks.h>
+#include "ErrorBase.h"
+
+class DashboardBase : public ErrorBase {
+public:
+ virtual void GetStatusBuffer(char** userStatusData, INT32* userStatusDataSize) = 0;
+ virtual void Flush() = 0;
+ virtual ~DashboardBase() {}
+protected:
+ DashboardBase() {}
+private:
+ DISALLOW_COPY_AND_ASSIGN(DashboardBase);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/DigitalInput.cpp b/aos/externals/WPILib/WPILib/DigitalInput.cpp
new file mode 100644
index 0000000..8858e50
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DigitalInput.cpp
@@ -0,0 +1,201 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "DigitalInput.h"
+#include "DigitalModule.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+// TODO: This is not a good place for this...
+Resource *interruptsResource = NULL;
+
+/**
+ * Create an instance of a DigitalInput.
+ * Creates a digital input given a slot and channel. Common creation routine
+ * for all constructors.
+ */
+void DigitalInput::InitDigitalInput(UINT8 moduleNumber, UINT32 channel)
+{
+ char buf[64];
+ Resource::CreateResourceObject(&interruptsResource, tInterrupt::kNumSystems);
+ if (!CheckDigitalModule(moduleNumber))
+ {
+ snprintf(buf, 64, "Digital Module %d", moduleNumber);
+ wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf);
+ return;
+ }
+ if (!CheckDigitalChannel(channel))
+ {
+ snprintf(buf, 64, "Digital Channel %d", channel);
+ wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+ return;
+ }
+ m_channel = channel;
+ m_module = DigitalModule::GetInstance(moduleNumber);
+ m_module->AllocateDIO(channel, true);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_DigitalInput, channel, moduleNumber - 1);
+}
+
+/**
+ * Create an instance of a Digital Input class.
+ * Creates a digital input given a channel and uses the default module.
+ *
+ * @param channel The digital channel (1..14).
+ */
+DigitalInput::DigitalInput(UINT32 channel)
+{
+ InitDigitalInput(GetDefaultDigitalModule(), channel);
+}
+
+/**
+ * Create an instance of a Digital Input class.
+ * Creates a digital input given an channel and module.
+ *
+ * @param moduleNumber The digital module (1 or 2).
+ * @param channel The digital channel (1..14).
+ */
+DigitalInput::DigitalInput(UINT8 moduleNumber, UINT32 channel)
+{
+ InitDigitalInput(moduleNumber, channel);
+}
+
+/**
+ * Free resources associated with the Digital Input class.
+ */
+DigitalInput::~DigitalInput()
+{
+ if (StatusIsFatal()) return;
+ if (m_manager != NULL)
+ {
+ delete m_manager;
+ delete m_interrupt;
+ interruptsResource->Free(m_interruptIndex);
+ }
+ m_module->FreeDIO(m_channel);
+}
+
+/*
+ * Get the value from a digital input channel.
+ * Retrieve the value of a single digital input channel from the FPGA.
+ */
+UINT32 DigitalInput::Get()
+{
+ if (StatusIsFatal()) return 0;
+ return m_module->GetDIO(m_channel);
+}
+
+/**
+ * @return The GPIO channel number that this object represents.
+ */
+UINT32 DigitalInput::GetChannel()
+{
+ return m_channel;
+}
+
+/**
+ * @return The value to be written to the channel field of a routing mux.
+ */
+UINT32 DigitalInput::GetChannelForRouting()
+{
+ return DigitalModule::RemapDigitalChannel(GetChannel() - 1);
+}
+
+/**
+ * @return The value to be written to the module field of a routing mux.
+ */
+UINT32 DigitalInput::GetModuleForRouting()
+{
+ if (StatusIsFatal()) return 0;
+ return m_module->GetNumber() - 1;
+}
+
+/**
+ * @return The value to be written to the analog trigger field of a routing mux.
+ */
+bool DigitalInput::GetAnalogTriggerForRouting()
+{
+ return false;
+}
+
+/**
+ * Request interrupts asynchronously on this digital input.
+ * @param handler The address of the interrupt handler function of type tInterruptHandler that
+ * will be called whenever there is an interrupt on the digitial input port.
+ * Request interrupts in synchronus mode where the user program interrupt handler will be
+ * called when an interrupt occurs.
+ * The default is interrupt on rising edges only.
+ */
+void DigitalInput::RequestInterrupts(tInterruptHandler handler, void *param)
+{
+ if (StatusIsFatal()) return;
+ UINT32 index = interruptsResource->Allocate("Async Interrupt");
+ if (index == ~0ul)
+ {
+ CloneError(interruptsResource);
+ return;
+ }
+ m_interruptIndex = index;
+
+ // Creates a manager too
+ AllocateInterrupts(false);
+
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_interrupt->writeConfig_WaitForAck(false, &localStatus);
+ m_interrupt->writeConfig_Source_AnalogTrigger(GetAnalogTriggerForRouting(), &localStatus);
+ m_interrupt->writeConfig_Source_Channel(GetChannelForRouting(), &localStatus);
+ m_interrupt->writeConfig_Source_Module(GetModuleForRouting(), &localStatus);
+ SetUpSourceEdge(true, false);
+
+ m_manager->registerHandler(handler, param, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Request interrupts synchronously on this digital input.
+ * Request interrupts in synchronus mode where the user program will have to explicitly
+ * wait for the interrupt to occur.
+ * The default is interrupt on rising edges only.
+ */
+void DigitalInput::RequestInterrupts()
+{
+ if (StatusIsFatal()) return;
+ UINT32 index = interruptsResource->Allocate("Sync Interrupt");
+ if (index == ~0ul)
+ {
+ CloneError(interruptsResource);
+ return;
+ }
+ m_interruptIndex = index;
+
+ AllocateInterrupts(true);
+
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_interrupt->writeConfig_Source_AnalogTrigger(GetAnalogTriggerForRouting(), &localStatus);
+ m_interrupt->writeConfig_Source_Channel(GetChannelForRouting(), &localStatus);
+ m_interrupt->writeConfig_Source_Module(GetModuleForRouting(), &localStatus);
+ SetUpSourceEdge(true, false);
+ wpi_setError(localStatus);
+}
+
+void DigitalInput::SetUpSourceEdge(bool risingEdge, bool fallingEdge)
+{
+ if (StatusIsFatal()) return;
+ if (m_interrupt == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "You must call RequestInterrupts before SetUpSourceEdge");
+ return;
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ if (m_interrupt != NULL)
+ {
+ m_interrupt->writeConfig_RisingEdge(risingEdge, &localStatus);
+ m_interrupt->writeConfig_FallingEdge(fallingEdge, &localStatus);
+ }
+ wpi_setError(localStatus);
+}
+
diff --git a/aos/externals/WPILib/WPILib/DigitalInput.h b/aos/externals/WPILib/WPILib/DigitalInput.h
new file mode 100644
index 0000000..e847ec1
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DigitalInput.h
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef DIGITAL_INPUT_H_
+#define DIGITAL_INPUT_H_
+
+class DigitalModule;
+
+#include "DigitalSource.h"
+
+/**
+ * Class to read a digital input.
+ * This class will read digital inputs and return the current value on the channel. Other devices
+ * such as encoders, gear tooth sensors, etc. that are implemented elsewhere will automatically
+ * allocate digital inputs and outputs as required. This class is only for devices like switches
+ * etc. that aren't implemented anywhere else.
+ */
+class DigitalInput : public DigitalSource {
+public:
+ explicit DigitalInput(UINT32 channel);
+ DigitalInput(UINT8 moduleNumber, UINT32 channel);
+ virtual ~DigitalInput();
+ UINT32 Get();
+ UINT32 GetChannel();
+
+ // Digital Source Interface
+ virtual UINT32 GetChannelForRouting();
+ virtual UINT32 GetModuleForRouting();
+ virtual bool GetAnalogTriggerForRouting();
+
+ // Interruptable Interface
+ virtual void RequestInterrupts(tInterruptHandler handler, void *param=NULL); ///< Asynchronus handler version.
+ virtual void RequestInterrupts(); ///< Synchronus Wait version.
+ void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
+
+private:
+ void InitDigitalInput(UINT8 moduleNumber, UINT32 channel);
+ UINT32 m_channel;
+ DigitalModule *m_module;
+ bool m_lastValue;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/DigitalModule.cpp b/aos/externals/WPILib/WPILib/DigitalModule.cpp
new file mode 100644
index 0000000..3e7f728
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DigitalModule.cpp
@@ -0,0 +1,530 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "DigitalModule.h"
+#include "I2C.h"
+#include "PWM.h"
+#include "Resource.h"
+#include "Synchronized.h"
+#include "WPIErrors.h"
+#include <math.h>
+#include <taskLib.h>
+
+static Resource *DIOChannels = NULL;
+static Resource *DO_PWMGenerators[tDIO::kNumSystems] = {NULL};
+
+/**
+ * Get an instance of an Digital Module.
+ * Singleton digital module creation where a module is allocated on the first use
+ * and the same module is returned on subsequent uses.
+ *
+ * @param moduleNumber The digital module to get (1 or 2).
+ */
+DigitalModule* DigitalModule::GetInstance(UINT8 moduleNumber)
+{
+ if (CheckDigitalModule(moduleNumber))
+ {
+ return (DigitalModule *)GetModule(nLoadOut::kModuleType_Digital, moduleNumber);
+ }
+
+ // If this wasn't caught before now, make sure we say what's wrong before we crash
+ char buf[64];
+ snprintf(buf, 64, "Digital Module %d", moduleNumber);
+ wpi_setGlobalWPIErrorWithContext(ModuleIndexOutOfRange, buf);
+
+ return NULL;
+}
+
+/**
+ * Create a new instance of an digital module.
+ * Create an instance of the digital module object. Initialize all the parameters
+ * to reasonable values on start.
+ * Setting a global value on an digital module can be done only once unless subsequent
+ * values are set the previously set value.
+ * Digital modules are a singleton, so the constructor is never called outside of this class.
+ *
+ * @param moduleNumber The digital module to create (1 or 2).
+ */
+DigitalModule::DigitalModule(UINT8 moduleNumber)
+ : Module(nLoadOut::kModuleType_Digital, moduleNumber)
+ , m_fpgaDIO (NULL)
+{
+ Resource::CreateResourceObject(&DIOChannels, tDIO::kNumSystems * kDigitalChannels);
+ Resource::CreateResourceObject(&DO_PWMGenerators[m_moduleNumber - 1], tDIO::kNumDO_PWMDutyCycleElements);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_fpgaDIO = tDIO::create(m_moduleNumber - 1, &localStatus);
+ wpi_setError(localStatus);
+
+ // Make sure that the 9403 IONode has had a chance to initialize before continuing.
+ while(m_fpgaDIO->readLoopTiming(&localStatus) == 0) taskDelay(1);
+ if (m_fpgaDIO->readLoopTiming(&localStatus) != kExpectedLoopTiming)
+ {
+ char err[128];
+ sprintf(err, "DIO LoopTiming: %d, expecting: %d\n", m_fpgaDIO->readLoopTiming(&localStatus), kExpectedLoopTiming);
+ wpi_setWPIErrorWithContext(LoopTimingError, err);
+ }
+ m_fpgaDIO->writePWMConfig_Period(PWM::kDefaultPwmPeriod, &localStatus);
+ m_fpgaDIO->writePWMConfig_MinHigh(PWM::kDefaultMinPwmHigh, &localStatus);
+
+ // Ensure that PWM output values are set to OFF
+ for (UINT32 pwm_index = 1; pwm_index <= kPwmChannels; pwm_index++)
+ {
+ SetPWM(pwm_index, PWM::kPwmDisabled);
+ SetPWMPeriodScale(pwm_index, 3); // Set all to 4x by default.
+ }
+
+ // Turn off all relay outputs.
+ m_fpgaDIO->writeSlowValue_RelayFwd(0, &localStatus);
+ m_fpgaDIO->writeSlowValue_RelayRev(0, &localStatus);
+ wpi_setError(localStatus);
+
+ // Create a semaphore to protect changes to the digital output values
+ m_digitalSemaphore = semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+
+ // Create a semaphore to protect changes to the relay values
+ m_relaySemaphore = semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+
+ // Create a semaphore to protect changes to the DO PWM config
+ m_doPwmSemaphore = semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+
+ AddToSingletonList();
+}
+
+DigitalModule::~DigitalModule()
+{
+ semDelete(m_doPwmSemaphore);
+ m_doPwmSemaphore = NULL;
+ semDelete(m_relaySemaphore);
+ m_relaySemaphore = NULL;
+ semDelete(m_digitalSemaphore);
+ m_digitalSemaphore = NULL;
+ delete m_fpgaDIO;
+}
+
+/**
+ * Set a PWM channel to the desired value. The values range from 0 to 255 and the period is controlled
+ * by the PWM Period and MinHigh registers.
+ *
+ * @param channel The PWM channel to set.
+ * @param value The PWM value to set.
+ */
+void DigitalModule::SetPWM(UINT32 channel, UINT8 value)
+{
+ CheckPWMChannel(channel);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_fpgaDIO->writePWMValue(channel - 1, value, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Get a value from a PWM channel. The values range from 0 to 255.
+ *
+ * @param channel The PWM channel to read from.
+ * @return The raw PWM value.
+ */
+UINT8 DigitalModule::GetPWM(UINT32 channel)
+{
+ CheckPWMChannel(channel);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ return m_fpgaDIO->readPWMValue(channel - 1, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Set how how often the PWM signal is squelched, thus scaling the period.
+ *
+ * @param channel The PWM channel to configure.
+ * @param squelchMask The 2-bit mask of outputs to squelch.
+ */
+void DigitalModule::SetPWMPeriodScale(UINT32 channel, UINT32 squelchMask)
+{
+ CheckPWMChannel(channel);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_fpgaDIO->writePWMPeriodScale(channel - 1, squelchMask, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Set the state of a relay.
+ * Set the state of a relay output to be forward. Relays have two outputs and each is
+ * independently set to 0v or 12v.
+ */
+void DigitalModule::SetRelayForward(UINT32 channel, bool on)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ CheckRelayChannel(channel);
+ {
+ Synchronized sync(m_relaySemaphore);
+ UINT8 forwardRelays = m_fpgaDIO->readSlowValue_RelayFwd(&localStatus);
+ if (on)
+ forwardRelays |= 1 << (channel - 1);
+ else
+ forwardRelays &= ~(1 << (channel - 1));
+ m_fpgaDIO->writeSlowValue_RelayFwd(forwardRelays, &localStatus);
+ }
+ wpi_setError(localStatus);
+}
+
+/**
+ * Set the state of a relay.
+ * Set the state of a relay output to be reverse. Relays have two outputs and each is
+ * independently set to 0v or 12v.
+ */
+void DigitalModule::SetRelayReverse(UINT32 channel, bool on)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ CheckRelayChannel(channel);
+ {
+ Synchronized sync(m_relaySemaphore);
+ UINT8 reverseRelays = m_fpgaDIO->readSlowValue_RelayRev(&localStatus);
+ if (on)
+ reverseRelays |= 1 << (channel - 1);
+ else
+ reverseRelays &= ~(1 << (channel - 1));
+ m_fpgaDIO->writeSlowValue_RelayRev(reverseRelays, &localStatus);
+ }
+ wpi_setError(localStatus);
+}
+
+/**
+ * Get the current state of the forward relay channel
+ */
+bool DigitalModule::GetRelayForward(UINT32 channel)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT8 forwardRelays = m_fpgaDIO->readSlowValue_RelayFwd(&localStatus);
+ wpi_setError(localStatus);
+ return (forwardRelays & (1 << (channel - 1))) != 0;
+}
+
+/**
+ * Get the current state of all of the forward relay channels on this module.
+ */
+UINT8 DigitalModule::GetRelayForward()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT8 forwardRelays = m_fpgaDIO->readSlowValue_RelayFwd(&localStatus);
+ wpi_setError(localStatus);
+ return forwardRelays;
+}
+
+/**
+ * Get the current state of the reverse relay channel
+ */
+bool DigitalModule::GetRelayReverse(UINT32 channel)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT8 reverseRelays = m_fpgaDIO->readSlowValue_RelayRev(&localStatus);
+ wpi_setError(localStatus);
+ return (reverseRelays & (1 << (channel - 1))) != 0;
+
+}
+
+/**
+ * Get the current state of all of the reverse relay channels on this module.
+ */
+UINT8 DigitalModule::GetRelayReverse()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT8 reverseRelays = m_fpgaDIO->readSlowValue_RelayRev(&localStatus);
+ wpi_setError(localStatus);
+ return reverseRelays;
+}
+
+
+/**
+ * Allocate Digital I/O channels.
+ * Allocate channels so that they are not accidently reused. Also the direction is set at the
+ * time of the allocation.
+ *
+ * @param channel The Digital I/O channel
+ * @param input If true open as input; if false open as output
+ * @return Was successfully allocated
+ */
+bool DigitalModule::AllocateDIO(UINT32 channel, bool input)
+{
+ char buf[64];
+ snprintf(buf, 64, "DIO %d (Module %d)", channel, m_moduleNumber);
+ if (DIOChannels->Allocate(kDigitalChannels * (m_moduleNumber - 1) + channel - 1, buf) == ~0ul) return false;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ {
+ Synchronized sync(m_digitalSemaphore);
+ UINT32 bitToSet = 1 << (RemapDigitalChannel(channel - 1));
+ UINT32 outputEnable = m_fpgaDIO->readOutputEnable(&localStatus);
+ UINT32 outputEnableValue;
+ if (input)
+ {
+ outputEnableValue = outputEnable & (~bitToSet); // clear the bit for read
+ }
+ else
+ {
+ outputEnableValue = outputEnable | bitToSet; // set the bit for write
+ }
+ m_fpgaDIO->writeOutputEnable(outputEnableValue, &localStatus);
+ }
+ wpi_setError(localStatus);
+ return true;
+}
+
+/**
+ * Free the resource associated with a digital I/O channel.
+ *
+ * @param channel The Digital I/O channel to free
+ */
+void DigitalModule::FreeDIO(UINT32 channel)
+{
+ DIOChannels->Free(kDigitalChannels * (m_moduleNumber - 1) + channel - 1);
+}
+
+/**
+ * Write a digital I/O bit to the FPGA.
+ * Set a single value on a digital I/O channel.
+ *
+ * @param channel The Digital I/O channel
+ * @param value The state to set the digital channel (if it is configured as an output)
+ */
+void DigitalModule::SetDIO(UINT32 channel, short value)
+{
+ if (value != 0 && value != 1)
+ {
+ wpi_setWPIError(NonBinaryDigitalValue);
+ if (value != 0)
+ value = 1;
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ {
+ Synchronized sync(m_digitalSemaphore);
+ UINT16 currentDIO = m_fpgaDIO->readDO(&localStatus);
+ if(value == 0)
+ {
+ currentDIO = currentDIO & ~(1 << RemapDigitalChannel(channel - 1));
+ }
+ else if (value == 1)
+ {
+ currentDIO = currentDIO | (1 << RemapDigitalChannel(channel - 1));
+ }
+ m_fpgaDIO->writeDO(currentDIO, &localStatus);
+ }
+ wpi_setError(localStatus);
+}
+
+/**
+ * Read a digital I/O bit from the FPGA.
+ * Get a single value from a digital I/O channel.
+ *
+ * @param channel The digital I/O channel
+ * @return The state of the specified channel
+ */
+bool DigitalModule::GetDIO(UINT32 channel)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 currentDIO = m_fpgaDIO->readDI(&localStatus);
+ wpi_setError(localStatus);
+
+ //Shift 00000001 over channel-1 places.
+ //AND it against the currentDIO
+ //if it == 0, then return false
+ //else return true
+ return ((currentDIO >> RemapDigitalChannel(channel - 1)) & 1) != 0;
+}
+
+/**
+ * Read the state of all the Digital I/O lines from the FPGA
+ * These are not remapped to logical order. They are still in hardware order.
+ */
+UINT16 DigitalModule::GetDIO()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 currentDIO = m_fpgaDIO->readDI(&localStatus);
+ wpi_setError(localStatus);
+ return currentDIO;
+}
+
+/**
+ * Read the direction of a the Digital I/O lines
+ * A 1 bit means output and a 0 bit means input.
+ *
+ * @param channel The digital I/O channel
+ * @return The direction of the specified channel
+ */
+bool DigitalModule::GetDIODirection(UINT32 channel)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 currentOutputEnable = m_fpgaDIO->readOutputEnable(&localStatus);
+ wpi_setError(localStatus);
+
+ //Shift 00000001 over channel-1 places.
+ //AND it against the currentOutputEnable
+ //if it == 0, then return false
+ //else return true
+ return ((currentOutputEnable >> RemapDigitalChannel(channel - 1)) & 1) != 0;
+}
+
+/**
+ * Read the direction of all the Digital I/O lines from the FPGA
+ * A 1 bit means output and a 0 bit means input.
+ * These are not remapped to logical order. They are still in hardware order.
+ */
+UINT16 DigitalModule::GetDIODirection()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 currentOutputEnable = m_fpgaDIO->readOutputEnable(&localStatus);
+ wpi_setError(localStatus);
+ return currentOutputEnable;
+}
+
+/**
+ * Generate a single pulse.
+ * Write a pulse to the specified digital output channel. There can only be a single pulse going at any time.
+ *
+ * @param channel The Digital Output channel that the pulse should be output on
+ * @param pulseLength The active length of the pulse (in seconds)
+ */
+void DigitalModule::Pulse(UINT32 channel, float pulseLength)
+{
+ UINT16 mask = 1 << RemapDigitalChannel(channel - 1);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_fpgaDIO->writePulseLength((UINT8)(1.0e9 * pulseLength / (m_fpgaDIO->readLoopTiming(&localStatus) * 25)), &localStatus);
+ m_fpgaDIO->writePulse(mask, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Check a DIO line to see if it is currently generating a pulse.
+ *
+ * @return A pulse is in progress
+ */
+bool DigitalModule::IsPulsing(UINT32 channel)
+{
+ UINT16 mask = 1 << RemapDigitalChannel(channel - 1);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT16 pulseRegister = m_fpgaDIO->readPulse(&localStatus);
+ wpi_setError(localStatus);
+ return (pulseRegister & mask) != 0;
+}
+
+/**
+ * Check if any DIO line is currently generating a pulse.
+ *
+ * @return A pulse on some line is in progress
+ */
+bool DigitalModule::IsPulsing()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT16 pulseRegister = m_fpgaDIO->readPulse(&localStatus);
+ wpi_setError(localStatus);
+ return pulseRegister != 0;
+}
+
+/**
+ * Allocate a DO PWM Generator.
+ * Allocate PWM generators so that they are not accidently reused.
+ *
+ * @return PWM Generator refnum
+ */
+UINT32 DigitalModule::AllocateDO_PWM()
+{
+ char buf[64];
+ snprintf(buf, 64, "DO_PWM (Module: %d)", m_moduleNumber);
+ return DO_PWMGenerators[(m_moduleNumber - 1)]->Allocate(buf);
+}
+
+/**
+ * Free the resource associated with a DO PWM generator.
+ *
+ * @param pwmGenerator The pwmGen to free that was allocated with AllocateDO_PWM()
+ */
+void DigitalModule::FreeDO_PWM(UINT32 pwmGenerator)
+{
+ if (pwmGenerator == ~0ul) return;
+ DO_PWMGenerators[(m_moduleNumber - 1)]->Free(pwmGenerator);
+}
+
+/**
+ * Change the frequency of the DO PWM generator.
+ *
+ * The valid range is from 0.6 Hz to 19 kHz. The frequency resolution is logarithmic.
+ *
+ * @param rate The frequency to output all digital output PWM signals on this module.
+ */
+void DigitalModule::SetDO_PWMRate(float rate)
+{
+ // Currently rounding in the log rate domain... heavy weight toward picking a higher freq.
+ // TODO: Round in the linear rate domain.
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT8 pwmPeriodPower = (UINT8)(log(1.0 / (m_fpgaDIO->readLoopTiming(&localStatus) * 0.25E-6 * rate))/log(2.0) + 0.5);
+ m_fpgaDIO->writeDO_PWMConfig_PeriodPower(pwmPeriodPower, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Configure which DO channel the PWM siganl is output on
+ *
+ * @param pwmGenerator The generator index reserved by AllocateDO_PWM()
+ * @param channel The Digital Output channel to output on
+ */
+void DigitalModule::SetDO_PWMOutputChannel(UINT32 pwmGenerator, UINT32 channel)
+{
+ if (pwmGenerator == ~0ul) return;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ switch(pwmGenerator)
+ {
+ case 0:
+ m_fpgaDIO->writeDO_PWMConfig_OutputSelect_0(RemapDigitalChannel(channel - 1), &localStatus);
+ break;
+ case 1:
+ m_fpgaDIO->writeDO_PWMConfig_OutputSelect_1(RemapDigitalChannel(channel - 1), &localStatus);
+ break;
+ case 2:
+ m_fpgaDIO->writeDO_PWMConfig_OutputSelect_2(RemapDigitalChannel(channel - 1), &localStatus);
+ break;
+ case 3:
+ m_fpgaDIO->writeDO_PWMConfig_OutputSelect_3(RemapDigitalChannel(channel - 1), &localStatus);
+ break;
+ }
+ wpi_setError(localStatus);
+}
+
+/**
+ * Configure the duty-cycle of the PWM generator
+ *
+ * @param pwmGenerator The generator index reserved by AllocateDO_PWM()
+ * @param dutyCycle The percent duty cycle to output [0..1].
+ */
+void DigitalModule::SetDO_PWMDutyCycle(UINT32 pwmGenerator, float dutyCycle)
+{
+ if (pwmGenerator == ~0ul) return;
+ if (dutyCycle > 1.0) dutyCycle = 1.0;
+ if (dutyCycle < 0.0) dutyCycle = 0.0;
+ float rawDutyCycle = 256.0 * dutyCycle;
+ if (rawDutyCycle > 255.5) rawDutyCycle = 255.5;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ {
+ Synchronized sync(m_doPwmSemaphore);
+ UINT8 pwmPeriodPower = m_fpgaDIO->readDO_PWMConfig_PeriodPower(&localStatus);
+ if (pwmPeriodPower < 4)
+ {
+ // The resolution of the duty cycle drops close to the highest frequencies.
+ rawDutyCycle = rawDutyCycle / pow(2.0, 4 - pwmPeriodPower);
+ }
+ m_fpgaDIO->writeDO_PWMDutyCycle(pwmGenerator, (UINT8)rawDutyCycle, &localStatus);
+ }
+ wpi_setError(localStatus);
+}
+
+/**
+ * Return a pointer to an I2C object for this digital module
+ * The caller is responsible for deleting the pointer.
+ *
+ * @param address The address of the device on the I2C bus
+ * @return A pointer to an I2C object to talk to the device at address
+ */
+I2C* DigitalModule::GetI2C(UINT32 address)
+{
+ return new I2C(this, address);
+}
+
+
diff --git a/aos/externals/WPILib/WPILib/DigitalModule.h b/aos/externals/WPILib/WPILib/DigitalModule.h
new file mode 100644
index 0000000..e80beb6
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DigitalModule.h
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef DIGITAL_MODULE_H_
+#define DIGITAL_MODULE_H_
+
+#include "Module.h"
+#include "ChipObject.h"
+
+class I2C;
+
+const UINT32 kExpectedLoopTiming = 260;
+
+class DigitalModule: public Module
+{
+ friend class I2C;
+ friend class Module;
+
+protected:
+ explicit DigitalModule(UINT8 moduleNumber);
+ virtual ~DigitalModule();
+
+public:
+ void SetPWM(UINT32 channel, UINT8 value);
+ UINT8 GetPWM(UINT32 channel);
+ void SetPWMPeriodScale(UINT32 channel, UINT32 squelchMask);
+ void SetRelayForward(UINT32 channel, bool on);
+ void SetRelayReverse(UINT32 channel, bool on);
+ bool GetRelayForward(UINT32 channel);
+ UINT8 GetRelayForward();
+ bool GetRelayReverse(UINT32 channel);
+ UINT8 GetRelayReverse();
+ bool AllocateDIO(UINT32 channel, bool input);
+ void FreeDIO(UINT32 channel);
+ void SetDIO(UINT32 channel, short value);
+ bool GetDIO(UINT32 channel);
+ UINT16 GetDIO();
+ bool GetDIODirection(UINT32 channel);
+ UINT16 GetDIODirection();
+ void Pulse(UINT32 channel, float pulseLength);
+ bool IsPulsing(UINT32 channel);
+ bool IsPulsing();
+ UINT32 AllocateDO_PWM();
+ void FreeDO_PWM(UINT32 pwmGenerator);
+ void SetDO_PWMRate(float rate);
+ void SetDO_PWMDutyCycle(UINT32 pwmGenerator, float dutyCycle);
+ void SetDO_PWMOutputChannel(UINT32 pwmGenerator, UINT32 channel);
+
+ I2C* GetI2C(UINT32 address);
+
+ static DigitalModule* GetInstance(UINT8 moduleNumber);
+ static UINT8 RemapDigitalChannel(UINT32 channel) { return 15 - channel; }; // TODO: Need channel validation
+ static UINT8 UnmapDigitalChannel(UINT32 channel) { return 15 - channel; }; // TODO: Need channel validation
+
+private:
+ SEM_ID m_digitalSemaphore;
+ SEM_ID m_relaySemaphore;
+ SEM_ID m_doPwmSemaphore;
+ tDIO *m_fpgaDIO;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/DigitalOutput.cpp b/aos/externals/WPILib/WPILib/DigitalOutput.cpp
new file mode 100644
index 0000000..39c8e84
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DigitalOutput.cpp
@@ -0,0 +1,282 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "DigitalOutput.h"
+#include "DigitalModule.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+extern Resource *interruptsResource;
+
+/**
+ * Create an instance of a DigitalOutput.
+ * Creates a digital output given a slot and channel. Common creation routine
+ * for all constructors.
+ */
+void DigitalOutput::InitDigitalOutput(UINT8 moduleNumber, UINT32 channel)
+{
+ char buf[64];
+ if (!CheckDigitalModule(moduleNumber))
+ {
+ snprintf(buf, 64, "Digital Module %d", moduleNumber);
+ wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf);
+ return;
+ }
+ if (!CheckDigitalChannel(channel))
+ {
+ snprintf(buf, 64, "Digital Channel %d", channel);
+ wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+ return;
+ }
+ m_channel = channel;
+ m_pwmGenerator = ~0ul;
+ m_module = DigitalModule::GetInstance(moduleNumber);
+ m_module->AllocateDIO(m_channel, false);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_DigitalOutput, channel, moduleNumber - 1);
+}
+
+/**
+ * Create an instance of a digital output.
+ * Create a digital output given a channel. The default module is used.
+ *
+ * @param channel The digital channel (1..14).
+ */
+DigitalOutput::DigitalOutput(UINT32 channel)
+{
+ InitDigitalOutput(GetDefaultDigitalModule(), channel);
+}
+
+/**
+ * Create an instance of a digital output.
+ * Create an instance of a digital output given a module number and channel.
+ *
+ * @param moduleNumber The digital module (1 or 2).
+ * @param channel The digital channel (1..14).
+ */
+DigitalOutput::DigitalOutput(UINT8 moduleNumber, UINT32 channel)
+{
+ InitDigitalOutput(moduleNumber, channel);
+}
+
+/**
+ * Free the resources associated with a digital output.
+ */
+DigitalOutput::~DigitalOutput()
+{
+ if (StatusIsFatal()) return;
+ // Disable the PWM in case it was running.
+ DisablePWM();
+ m_module->FreeDIO(m_channel);
+}
+
+/**
+ * Set the value of a digital output.
+ * Set the value of a digital output to either one (true) or zero (false).
+ */
+void DigitalOutput::Set(UINT32 value)
+{
+ if (StatusIsFatal()) return;
+ m_module->SetDIO(m_channel, value);
+}
+
+/**
+ * @return The GPIO channel number that this object represents.
+ */
+UINT32 DigitalOutput::GetChannel()
+{
+ return m_channel;
+}
+
+/**
+ * Output a single pulse on the digital output line.
+ * Send a single pulse on the digital output line where the pulse diration is specified in seconds.
+ * Maximum pulse length is 0.0016 seconds.
+ * @param length The pulselength in seconds
+ */
+void DigitalOutput::Pulse(float length)
+{
+ if (StatusIsFatal()) return;
+ m_module->Pulse(m_channel, length);
+}
+
+/**
+ * Determine if the pulse is still going.
+ * Determine if a previously started pulse is still going.
+ */
+bool DigitalOutput::IsPulsing()
+{
+ if (StatusIsFatal()) return false;
+ return m_module->IsPulsing(m_channel);
+}
+
+/**
+ * Change the PWM frequency of the PWM output on a Digital Output line.
+ *
+ * The valid range is from 0.6 Hz to 19 kHz. The frequency resolution is logarithmic.
+ *
+ * There is only one PWM frequency per digital module.
+ *
+ * @param rate The frequency to output all digital output PWM signals on this module.
+ */
+void DigitalOutput::SetPWMRate(float rate)
+{
+ if (StatusIsFatal()) return;
+ m_module->SetDO_PWMRate(rate);
+}
+
+/**
+ * Enable a PWM Output on this line.
+ *
+ * Allocate one of the 4 DO PWM generator resources from this module.
+ *
+ * Supply the initial duty-cycle to output so as to avoid a glitch when first starting.
+ *
+ * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less)
+ * but is reduced the higher the frequency of the PWM signal is.
+ *
+ * @param initialDutyCycle The duty-cycle to start generating. [0..1]
+ */
+void DigitalOutput::EnablePWM(float initialDutyCycle)
+{
+ if (StatusIsFatal()) return;
+ if (m_pwmGenerator != ~0ul) return;
+ m_pwmGenerator = m_module->AllocateDO_PWM();
+ m_module->SetDO_PWMDutyCycle(m_pwmGenerator, initialDutyCycle);
+ m_module->SetDO_PWMOutputChannel(m_pwmGenerator, m_channel);
+}
+
+/**
+ * Change this line from a PWM output back to a static Digital Output line.
+ *
+ * Free up one of the 4 DO PWM generator resources that were in use.
+ */
+void DigitalOutput::DisablePWM()
+{
+ if (StatusIsFatal()) return;
+ // Disable the output by routing to a dead bit.
+ m_module->SetDO_PWMOutputChannel(m_pwmGenerator, kDigitalChannels);
+ m_module->FreeDO_PWM(m_pwmGenerator);
+ m_pwmGenerator = ~0ul;
+}
+
+/**
+ * Change the duty-cycle that is being generated on the line.
+ *
+ * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less)
+ * but is reduced the higher the frequency of the PWM signal is.
+ *
+ * @param dutyCycle The duty-cycle to change to. [0..1]
+ */
+void DigitalOutput::UpdateDutyCycle(float dutyCycle)
+{
+ if (StatusIsFatal()) return;
+ m_module->SetDO_PWMDutyCycle(m_pwmGenerator, dutyCycle);
+}
+
+/**
+ * @return The value to be written to the channel field of a routing mux.
+ */
+UINT32 DigitalOutput::GetChannelForRouting()
+{
+ return DigitalModule::RemapDigitalChannel(GetChannel() - 1);
+}
+
+/**
+ * @return The value to be written to the module field of a routing mux.
+ */
+UINT32 DigitalOutput::GetModuleForRouting()
+{
+ if (StatusIsFatal()) return 0;
+ return m_module->GetNumber() - 1;
+}
+
+/**
+ * @return The value to be written to the analog trigger field of a routing mux.
+ */
+bool DigitalOutput::GetAnalogTriggerForRouting()
+{
+ return false;
+}
+
+/**
+ * Request interrupts asynchronously on this digital output.
+ * @param handler The address of the interrupt handler function of type tInterruptHandler that
+ * will be called whenever there is an interrupt on the digitial output port.
+ * Request interrupts in synchronus mode where the user program interrupt handler will be
+ * called when an interrupt occurs.
+ * The default is interrupt on rising edges only.
+ */
+void DigitalOutput::RequestInterrupts(tInterruptHandler handler, void *param)
+{
+ if (StatusIsFatal()) return;
+ UINT32 index = interruptsResource->Allocate("Sync Interrupt");
+ if (index == ~0ul)
+ {
+ CloneError(interruptsResource);
+ return;
+ }
+ m_interruptIndex = index;
+
+ // Creates a manager too
+ AllocateInterrupts(false);
+
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_interrupt->writeConfig_WaitForAck(false, &localStatus);
+ m_interrupt->writeConfig_Source_AnalogTrigger(GetAnalogTriggerForRouting(), &localStatus);
+ m_interrupt->writeConfig_Source_Channel(GetChannelForRouting(), &localStatus);
+ m_interrupt->writeConfig_Source_Module(GetModuleForRouting(), &localStatus);
+ SetUpSourceEdge(true, false);
+
+ m_manager->registerHandler(handler, param, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Request interrupts synchronously on this digital output.
+ * Request interrupts in synchronus mode where the user program will have to explicitly
+ * wait for the interrupt to occur.
+ * The default is interrupt on rising edges only.
+ */
+void DigitalOutput::RequestInterrupts()
+{
+ if (StatusIsFatal()) return;
+ UINT32 index = interruptsResource->Allocate("Sync Interrupt");
+ if (index == ~0ul)
+ {
+ CloneError(interruptsResource);
+ return;
+ }
+ m_interruptIndex = index;
+
+ AllocateInterrupts(true);
+
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_interrupt->writeConfig_Source_AnalogTrigger(GetAnalogTriggerForRouting(), &localStatus);
+ m_interrupt->writeConfig_Source_Channel(GetChannelForRouting(), &localStatus);
+ m_interrupt->writeConfig_Source_Module(GetModuleForRouting(), &localStatus);
+ SetUpSourceEdge(true, false);
+ wpi_setError(localStatus);
+}
+
+void DigitalOutput::SetUpSourceEdge(bool risingEdge, bool fallingEdge)
+{
+ if (StatusIsFatal()) return;
+ if (m_interrupt == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "You must call RequestInterrupts before SetUpSourceEdge");
+ return;
+ }
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ if (m_interrupt != NULL)
+ {
+ m_interrupt->writeConfig_RisingEdge(risingEdge, &localStatus);
+ m_interrupt->writeConfig_FallingEdge(fallingEdge, &localStatus);
+ }
+ wpi_setError(localStatus);
+}
+
diff --git a/aos/externals/WPILib/WPILib/DigitalOutput.h b/aos/externals/WPILib/WPILib/DigitalOutput.h
new file mode 100644
index 0000000..645e130
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DigitalOutput.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef DIGITAL_OUTPUT_H_
+#define DIGITAL_OUTPUT_H_
+
+#include "DigitalSource.h"
+
+class DigitalModule;
+
+/**
+ * Class to write to digital outputs.
+ * Write values to the digital output channels. Other devices implemented elsewhere will allocate
+ * channels automatically so for those devices it shouldn't be done here.
+ */
+class DigitalOutput : public DigitalSource
+{
+public:
+ explicit DigitalOutput(UINT32 channel);
+ DigitalOutput(UINT8 moduleNumber, UINT32 channel);
+ virtual ~DigitalOutput();
+ void Set(UINT32 value);
+ UINT32 GetChannel();
+ void Pulse(float length);
+ bool IsPulsing();
+ void SetPWMRate(float rate);
+ void EnablePWM(float initialDutyCycle);
+ void DisablePWM();
+ void UpdateDutyCycle(float dutyCycle);
+
+ // Digital Source Interface
+ virtual UINT32 GetChannelForRouting();
+ virtual UINT32 GetModuleForRouting();
+ virtual bool GetAnalogTriggerForRouting();
+ virtual void RequestInterrupts(tInterruptHandler handler, void *param);
+ virtual void RequestInterrupts();
+
+ void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
+
+private:
+ void InitDigitalOutput(UINT8 moduleNumber, UINT32 channel);
+
+ UINT32 m_channel;
+ UINT32 m_pwmGenerator;
+ DigitalModule *m_module;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/DigitalSource.cpp b/aos/externals/WPILib/WPILib/DigitalSource.cpp
new file mode 100644
index 0000000..40cc75c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DigitalSource.cpp
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "DigitalSource.h"
+
+/**
+ * DigitalSource destructor.
+ */
+DigitalSource::~DigitalSource()
+{
+}
diff --git a/aos/externals/WPILib/WPILib/DigitalSource.h b/aos/externals/WPILib/WPILib/DigitalSource.h
new file mode 100644
index 0000000..1c427be
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DigitalSource.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef DIGITAL_SOURCE_H
+#define DIGITAL_SOURCE_H
+
+#include "InterruptableSensorBase.h"
+
+/**
+ * DigitalSource Interface.
+ * The DigitalSource represents all the possible inputs for a counter or a quadrature encoder. The source may be
+ * either a digital input or an analog input. If the caller just provides a channel, then a digital input will be
+ * constructed and freed when finished for the source. The source can either be a digital input or analog trigger
+ * but not both.
+ */
+class DigitalSource: public InterruptableSensorBase
+{
+public:
+ virtual ~DigitalSource();
+ virtual UINT32 GetChannelForRouting() = 0;
+ virtual UINT32 GetModuleForRouting() = 0;
+ virtual bool GetAnalogTriggerForRouting() = 0;
+ virtual void RequestInterrupts(tInterruptHandler handler, void *param) = 0;
+ virtual void RequestInterrupts() = 0;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/DoubleSolenoid.cpp b/aos/externals/WPILib/WPILib/DoubleSolenoid.cpp
new file mode 100644
index 0000000..0bd4d88
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DoubleSolenoid.cpp
@@ -0,0 +1,136 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "DoubleSolenoid.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+
+/**
+ * Common function to implement constructor behavior.
+ */
+void DoubleSolenoid::InitSolenoid()
+{
+ char buf[64];
+ if (!CheckSolenoidModule(m_moduleNumber))
+ {
+ snprintf(buf, 64, "Solenoid Module %d", m_moduleNumber);
+ wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf);
+ return;
+ }
+ if (!CheckSolenoidChannel(m_forwardChannel))
+ {
+ snprintf(buf, 64, "Solenoid Channel %d", m_forwardChannel);
+ wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+ return;
+ }
+ if (!CheckSolenoidChannel(m_reverseChannel))
+ {
+ snprintf(buf, 64, "Solenoid Channel %d", m_reverseChannel);
+ wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+ return;
+ }
+ Resource::CreateResourceObject(&m_allocated, tSolenoid::kNumDO7_0Elements * kSolenoidChannels);
+
+ snprintf(buf, 64, "Solenoid %d (Module %d)", m_forwardChannel, m_moduleNumber);
+ if (m_allocated->Allocate((m_moduleNumber - 1) * kSolenoidChannels + m_forwardChannel - 1, buf) == ~0ul)
+ {
+ CloneError(m_allocated);
+ return;
+ }
+ snprintf(buf, 64, "Solenoid %d (Module %d)", m_reverseChannel, m_moduleNumber);
+ if (m_allocated->Allocate((m_moduleNumber - 1) * kSolenoidChannels + m_reverseChannel - 1, buf) == ~0ul)
+ {
+ CloneError(m_allocated);
+ return;
+ }
+ m_forwardMask = 1 << (m_forwardChannel - 1);
+ m_reverseMask = 1 << (m_reverseChannel - 1);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Solenoid, m_forwardChannel, m_moduleNumber - 1);
+ nUsageReporting::report(nUsageReporting::kResourceType_Solenoid, m_reverseChannel, m_moduleNumber - 1);
+}
+
+/**
+ * Constructor.
+ *
+ * @param forwardChannel The forward channel on the module to control.
+ * @param reverseChannel The reverse channel on the module to control.
+ */
+DoubleSolenoid::DoubleSolenoid(UINT32 forwardChannel, UINT32 reverseChannel)
+ : SolenoidBase (GetDefaultSolenoidModule())
+ , m_forwardChannel (forwardChannel)
+ , m_reverseChannel (reverseChannel)
+{
+ InitSolenoid();
+}
+
+/**
+ * Constructor.
+ *
+ * @param moduleNumber The solenoid module (1 or 2).
+ * @param forwardChannel The forward channel on the module to control.
+ * @param reverseChannel The reverse channel on the module to control.
+ */
+DoubleSolenoid::DoubleSolenoid(UINT8 moduleNumber, UINT32 forwardChannel, UINT32 reverseChannel)
+ : SolenoidBase (moduleNumber)
+ , m_forwardChannel (forwardChannel)
+ , m_reverseChannel (reverseChannel)
+{
+ InitSolenoid();
+}
+
+/**
+ * Destructor.
+ */
+DoubleSolenoid::~DoubleSolenoid()
+{
+ if (CheckSolenoidModule(m_moduleNumber))
+ {
+ m_allocated->Free((m_moduleNumber - 1) * kSolenoidChannels + m_forwardChannel - 1);
+ m_allocated->Free((m_moduleNumber - 1) * kSolenoidChannels + m_reverseChannel - 1);
+ }
+}
+
+/**
+ * Set the value of a solenoid.
+ *
+ * @param value Move the solenoid to forward, reverse, or don't move it.
+ */
+void DoubleSolenoid::Set(Value value)
+{
+ if (StatusIsFatal()) return;
+ UINT8 rawValue = 0x00;
+
+ switch(value)
+ {
+ case kOff:
+ rawValue = 0x00;
+ break;
+ case kForward:
+ rawValue = m_forwardMask;
+ break;
+ case kReverse:
+ rawValue = m_reverseMask;
+ break;
+ }
+
+ SolenoidBase::Set(rawValue, m_forwardMask | m_reverseMask);
+}
+
+/**
+ * Read the current value of the solenoid.
+ *
+ * @return The current value of the solenoid.
+ */
+DoubleSolenoid::Value DoubleSolenoid::Get()
+{
+ if (StatusIsFatal()) return kOff;
+ UINT8 value = GetAll();
+
+ if (value & m_forwardMask) return kForward;
+ if (value & m_reverseMask) return kReverse;
+ return kOff;
+}
diff --git a/aos/externals/WPILib/WPILib/DoubleSolenoid.h b/aos/externals/WPILib/WPILib/DoubleSolenoid.h
new file mode 100644
index 0000000..d0de661
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DoubleSolenoid.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef DOUBLE_SOLENOID_H_
+#define DOUBLE_SOLENOID_H_
+
+#include "SolenoidBase.h"
+
+/**
+ * DoubleSolenoid class for running 2 channels of high voltage Digital Output
+ * (9472 module).
+ *
+ * The DoubleSolenoid class is typically used for pneumatics solenoids that
+ * have two positions controlled by two separate channels.
+ */
+class DoubleSolenoid : public SolenoidBase {
+public:
+ typedef enum {kOff, kForward, kReverse} Value;
+
+ explicit DoubleSolenoid(UINT32 forwardChannel, UINT32 reverseChannel);
+ DoubleSolenoid(UINT8 moduleNumber, UINT32 forwardChannel, UINT32 reverseChannel);
+ virtual ~DoubleSolenoid();
+ virtual void Set(Value value);
+ virtual Value Get();
+
+private:
+ virtual void InitSolenoid();
+
+ UINT32 m_forwardChannel; ///< The forward channel on the module to control.
+ UINT32 m_reverseChannel; ///< The reverse channel on the module to control.
+ UINT8 m_forwardMask; ///< The mask for the forward channel.
+ UINT8 m_reverseMask; ///< The mask for the reverse channel.
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/DriverStation.cpp b/aos/externals/WPILib/WPILib/DriverStation.cpp
new file mode 100644
index 0000000..6adb41f
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DriverStation.cpp
@@ -0,0 +1,498 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "DriverStation.h"
+#include "AnalogChannel.h"
+#include "Synchronized.h"
+#include "Timer.h"
+#include "NetworkCommunication/FRCComm.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "MotorSafetyHelper.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+#include <strLib.h>
+
+const UINT32 DriverStation::kBatteryModuleNumber;
+const UINT32 DriverStation::kBatteryChannel;
+const UINT32 DriverStation::kJoystickPorts;
+const UINT32 DriverStation::kJoystickAxes;
+const float DriverStation::kUpdatePeriod;
+DriverStation* DriverStation::m_instance = NULL;
+UINT8 DriverStation::m_updateNumber = 0;
+
+/**
+ * DriverStation contructor.
+ *
+ * This is only called once the first time GetInstance() is called
+ */
+DriverStation::DriverStation()
+ : m_controlData (NULL)
+ , m_digitalOut (0)
+ , m_batteryChannel (NULL)
+ , m_statusDataSemaphore (semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE))
+ , m_task ("DriverStation", (FUNCPTR)DriverStation::InitTask)
+ , m_dashboardHigh(m_statusDataSemaphore)
+ , m_dashboardLow(m_statusDataSemaphore)
+ , m_dashboardInUseHigh(&m_dashboardHigh)
+ , m_dashboardInUseLow(&m_dashboardLow)
+ , m_newControlData (0)
+ , m_packetDataAvailableSem (0)
+ , m_enhancedIO()
+ , m_waitForDataSem(0)
+ , m_approxMatchTimeOffset(-1.0)
+ , m_userInDisabled(false)
+ , m_userInAutonomous(false)
+ , m_userInTeleop(false)
+{
+ // Create a new semaphore
+ m_packetDataAvailableSem = semBCreate (SEM_Q_PRIORITY, SEM_EMPTY);
+ m_newControlData = semBCreate (0, SEM_EMPTY);
+
+ // Register that semaphore with the network communications task.
+ // It will signal when new packet data is available.
+ setNewDataSem(m_packetDataAvailableSem);
+
+ m_waitForDataSem = semBCreate (SEM_Q_PRIORITY, SEM_EMPTY);
+
+ m_controlData = new FRCCommonControlData;
+
+ // initialize packet number and control words to zero;
+ m_controlData->packetIndex = 0;
+ m_controlData->control = 0;
+
+ // set all joystick axis values to neutral; buttons to OFF
+ m_controlData->stick0Axis1 = m_controlData->stick0Axis2 = m_controlData->stick0Axis3 = 0;
+ m_controlData->stick1Axis1 = m_controlData->stick1Axis2 = m_controlData->stick1Axis3 = 0;
+ m_controlData->stick2Axis1 = m_controlData->stick2Axis2 = m_controlData->stick2Axis3 = 0;
+ m_controlData->stick3Axis1 = m_controlData->stick3Axis2 = m_controlData->stick3Axis3 = 0;
+ m_controlData->stick0Axis4 = m_controlData->stick0Axis5 = m_controlData->stick0Axis6 = 0;
+ m_controlData->stick1Axis4 = m_controlData->stick1Axis5 = m_controlData->stick1Axis6 = 0;
+ m_controlData->stick2Axis4 = m_controlData->stick2Axis5 = m_controlData->stick2Axis6 = 0;
+ m_controlData->stick3Axis4 = m_controlData->stick3Axis5 = m_controlData->stick3Axis6 = 0;
+ m_controlData->stick0Buttons = 0;
+ m_controlData->stick1Buttons = 0;
+ m_controlData->stick2Buttons = 0;
+ m_controlData->stick3Buttons = 0;
+
+ // initialize the analog and digital data.
+ m_controlData->analog1 = 0;
+ m_controlData->analog2 = 0;
+ m_controlData->analog3 = 0;
+ m_controlData->analog4 = 0;
+ m_controlData->dsDigitalIn = 0;
+
+ m_batteryChannel = new AnalogChannel(kBatteryModuleNumber, kBatteryChannel);
+
+ AddToSingletonList();
+
+ if (!m_task.Start((INT32)this))
+ {
+ wpi_setWPIError(DriverStationTaskError);
+ }
+}
+
+DriverStation::~DriverStation()
+{
+ m_task.Stop();
+ semDelete(m_statusDataSemaphore);
+ delete m_batteryChannel;
+ delete m_controlData;
+ m_instance = NULL;
+ semDelete(m_waitForDataSem);
+ // Unregister our semaphore.
+ setNewDataSem(0);
+ semDelete(m_packetDataAvailableSem);
+}
+
+void DriverStation::InitTask(DriverStation *ds)
+{
+ ds->Run();
+}
+
+void DriverStation::Run()
+{
+ int period = 0;
+ while (true)
+ {
+ semTake(m_packetDataAvailableSem, WAIT_FOREVER);
+ SetData();
+ m_enhancedIO.UpdateData();
+ GetData();
+ semFlush(m_waitForDataSem);
+ if (++period >= 4)
+ {
+ MotorSafetyHelper::CheckMotors();
+ period = 0;
+ }
+ if (m_userInDisabled)
+ FRC_NetworkCommunication_observeUserProgramDisabled();
+ if (m_userInAutonomous)
+ FRC_NetworkCommunication_observeUserProgramAutonomous();
+ if (m_userInTeleop)
+ FRC_NetworkCommunication_observeUserProgramTeleop();
+ }
+}
+
+/**
+ * Return a pointer to the singleton DriverStation.
+ */
+DriverStation* DriverStation::GetInstance()
+{
+ if (m_instance == NULL)
+ {
+ m_instance = new DriverStation();
+ }
+ return m_instance;
+}
+
+/**
+ * Copy data from the DS task for the user.
+ * If no new data exists, it will just be returned, otherwise
+ * the data will be copied from the DS polling loop.
+ */
+void DriverStation::GetData()
+{
+ static bool lastEnabled = false;
+ getCommonControlData(m_controlData, WAIT_FOREVER);
+ if (!lastEnabled && IsEnabled())
+ {
+ // If starting teleop, assume that autonomous just took up 15 seconds
+ if (IsAutonomous())
+ m_approxMatchTimeOffset = Timer::GetFPGATimestamp();
+ else
+ m_approxMatchTimeOffset = Timer::GetFPGATimestamp() - 15.0;
+ }
+ else if (lastEnabled && !IsEnabled())
+ {
+ m_approxMatchTimeOffset = -1.0;
+ }
+ lastEnabled = IsEnabled();
+ semGive(m_newControlData);
+}
+
+/**
+ * Copy status data from the DS task for the user.
+ */
+void DriverStation::SetData()
+{
+ char *userStatusDataHigh;
+ INT32 userStatusDataHighSize;
+ char *userStatusDataLow;
+ INT32 userStatusDataLowSize;
+
+ Synchronized sync(m_statusDataSemaphore);
+
+ m_dashboardInUseHigh->GetStatusBuffer(&userStatusDataHigh, &userStatusDataHighSize);
+ m_dashboardInUseLow->GetStatusBuffer(&userStatusDataLow, &userStatusDataLowSize);
+ setStatusData(GetBatteryVoltage(), m_digitalOut, m_updateNumber,
+ userStatusDataHigh, userStatusDataHighSize, userStatusDataLow, userStatusDataLowSize, WAIT_FOREVER);
+
+ m_dashboardInUseHigh->Flush();
+ m_dashboardInUseLow->Flush();
+}
+
+/**
+ * Read the battery voltage from the specified AnalogChannel.
+ *
+ * This accessor assumes that the battery voltage is being measured
+ * through the voltage divider on an analog breakout.
+ *
+ * @return The battery voltage.
+ */
+float DriverStation::GetBatteryVoltage()
+{
+ if (m_batteryChannel == NULL)
+ wpi_setWPIError(NullParameter);
+
+ // The Analog bumper has a voltage divider on the battery source.
+ // Vbatt *--/\/\/\--* Vsample *--/\/\/\--* Gnd
+ // 680 Ohms 1000 Ohms
+ return m_batteryChannel->GetAverageVoltage() * (1680.0 / 1000.0);
+}
+
+/**
+ * Get the value of the axis on a joystick.
+ * This depends on the mapping of the joystick connected to the specified port.
+ *
+ * @param stick The joystick to read.
+ * @param axis The analog axis value to read from the joystick.
+ * @return The value of the axis on the joystick.
+ */
+float DriverStation::GetStickAxis(UINT32 stick, UINT32 axis)
+{
+ if (axis < 1 || axis > kJoystickAxes)
+ {
+ wpi_setWPIError(BadJoystickAxis);
+ return 0.0;
+ }
+
+ INT8 value;
+ switch (stick)
+ {
+ case 1:
+ value = m_controlData->stick0Axes[axis-1];
+ break;
+ case 2:
+ value = m_controlData->stick1Axes[axis-1];
+ break;
+ case 3:
+ value = m_controlData->stick2Axes[axis-1];
+ break;
+ case 4:
+ value = m_controlData->stick3Axes[axis-1];
+ break;
+ default:
+ wpi_setWPIError(BadJoystickIndex);
+ return 0.0;
+ }
+
+ float result;
+ if (value < 0)
+ result = ((float) value) / 128.0;
+ else
+ result = ((float) value) / 127.0;
+ wpi_assert(result <= 1.0 && result >= -1.0);
+ if (result > 1.0)
+ result = 1.0;
+ else if (result < -1.0)
+ result = -1.0;
+ return result;
+}
+
+/**
+ * The state of the buttons on the joystick.
+ * 12 buttons (4 msb are unused) from the joystick.
+ *
+ * @param stick The joystick to read.
+ * @return The state of the buttons on the joystick.
+ */
+short DriverStation::GetStickButtons(UINT32 stick)
+{
+ if (stick < 1 || stick > 4)
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "stick must be between 1 and 4");
+
+ switch (stick)
+ {
+ case 1:
+ return m_controlData->stick0Buttons;
+ case 2:
+ return m_controlData->stick1Buttons;
+ case 3:
+ return m_controlData->stick2Buttons;
+ case 4:
+ return m_controlData->stick3Buttons;
+ }
+ return 0;
+}
+
+// 5V divided by 10 bits
+#define kDSAnalogInScaling ((float)(5.0 / 1023.0))
+
+/**
+ * Get an analog voltage from the Driver Station.
+ * The analog values are returned as voltage values for the Driver Station analog inputs.
+ * These inputs are typically used for advanced operator interfaces consisting of potentiometers
+ * or resistor networks representing values on a rotary switch.
+ *
+ * @param channel The analog input channel on the driver station to read from. Valid range is 1 - 4.
+ * @return The analog voltage on the input.
+ */
+float DriverStation::GetAnalogIn(UINT32 channel)
+{
+ if (channel < 1 || channel > 4)
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 4");
+
+ static UINT8 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationCIO, channel, nUsageReporting::kDriverStationCIO_Analog);
+ reported_mask |= (1 >> channel);
+ }
+
+ switch (channel)
+ {
+ case 1:
+ return kDSAnalogInScaling * m_controlData->analog1;
+ case 2:
+ return kDSAnalogInScaling * m_controlData->analog2;
+ case 3:
+ return kDSAnalogInScaling * m_controlData->analog3;
+ case 4:
+ return kDSAnalogInScaling * m_controlData->analog4;
+ }
+ return 0.0;
+}
+
+/**
+ * Get values from the digital inputs on the Driver Station.
+ * Return digital values from the Drivers Station. These values are typically used for buttons
+ * and switches on advanced operator interfaces.
+ * @param channel The digital input to get. Valid range is 1 - 8.
+ */
+bool DriverStation::GetDigitalIn(UINT32 channel)
+{
+ if (channel < 1 || channel > 8)
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 8");
+
+ static UINT8 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationCIO, channel, nUsageReporting::kDriverStationCIO_DigitalIn);
+ reported_mask |= (1 >> channel);
+ }
+
+ return ((m_controlData->dsDigitalIn >> (channel-1)) & 0x1) ? true : false;
+}
+
+/**
+ * Set a value for the digital outputs on the Driver Station.
+ *
+ * Control digital outputs on the Drivers Station. These values are typically used for
+ * giving feedback on a custom operator station such as LEDs.
+ *
+ * @param channel The digital output to set. Valid range is 1 - 8.
+ * @param value The state to set the digital output.
+ */
+void DriverStation::SetDigitalOut(UINT32 channel, bool value)
+{
+ if (channel < 1 || channel > 8)
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 8");
+
+ static UINT8 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationCIO, channel, nUsageReporting::kDriverStationCIO_DigitalOut);
+ reported_mask |= (1 >> channel);
+ }
+
+ m_digitalOut &= ~(0x1 << (channel-1));
+ m_digitalOut |= ((UINT8)value << (channel-1));
+}
+
+/**
+ * Get a value that was set for the digital outputs on the Driver Station.
+ * @param channel The digital ouput to monitor. Valid range is 1 through 8.
+ * @return A digital value being output on the Drivers Station.
+ */
+bool DriverStation::GetDigitalOut(UINT32 channel)
+{
+ if (channel < 1 || channel > 8)
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 8");
+
+ return ((m_digitalOut >> (channel-1)) & 0x1) ? true : false;;
+}
+
+bool DriverStation::IsEnabled()
+{
+ return m_controlData->enabled;
+}
+
+bool DriverStation::IsDisabled()
+{
+ return !m_controlData->enabled;
+}
+
+bool DriverStation::IsAutonomous()
+{
+ return m_controlData->autonomous;
+}
+
+bool DriverStation::IsOperatorControl()
+{
+ return !m_controlData->autonomous;
+}
+
+/**
+ * Has a new control packet from the driver station arrived since the last time this function was called?
+ * Warning: If you call this function from more than one place at the same time,
+ * you will not get the get the intended behavior
+ * @return True if the control data has been updated since the last call.
+ */
+bool DriverStation::IsNewControlData()
+{
+ return semTake(m_newControlData, NO_WAIT) == 0;
+}
+
+/**
+ * Is the driver station attached to a Field Management System?
+ * Note: This does not work with the Blue DS.
+ * @return True if the robot is competing on a field being controlled by a Field Management System
+ */
+bool DriverStation::IsFMSAttached()
+{
+ return m_controlData->fmsAttached;
+}
+
+/**
+ * Return the DS packet number.
+ * The packet number is the index of this set of data returned by the driver station.
+ * Each time new data is received, the packet number (included with the sent data) is returned.
+ * @return The driver station packet number
+ */
+UINT32 DriverStation::GetPacketNumber()
+{
+ return m_controlData->packetIndex;
+}
+
+/**
+ * Return the alliance that the driver station says it is on.
+ * This could return kRed or kBlue
+ * @return The Alliance enum
+ */
+DriverStation::Alliance DriverStation::GetAlliance()
+{
+ if (m_controlData->dsID_Alliance == 'R') return kRed;
+ if (m_controlData->dsID_Alliance == 'B') return kBlue;
+ wpi_assert(false);
+ return kInvalid;
+}
+
+/**
+ * Return the driver station location on the field
+ * This could return 1, 2, or 3
+ * @return The location of the driver station
+ */
+UINT32 DriverStation::GetLocation()
+{
+ wpi_assert ((m_controlData->dsID_Position >= '1') && (m_controlData->dsID_Position <= '3'));
+ return m_controlData->dsID_Position - '0';
+}
+
+/**
+ * Wait until a new packet comes from the driver station
+ * This blocks on a semaphore, so the waiting is efficient.
+ * This is a good way to delay processing until there is new driver station data to act on
+ */
+void DriverStation::WaitForData()
+{
+ semTake(m_waitForDataSem, WAIT_FOREVER);
+}
+
+/**
+ * Return the approximate match time
+ * The FMS does not currently send the official match time to the robots
+ * This returns the time since the enable signal sent from the Driver Station
+ * At the beginning of autonomous, the time is reset to 0.0 seconds
+ * At the beginning of teleop, the time is reset to +15.0 seconds
+ * If the robot is disabled, this returns 0.0 seconds
+ * Warning: This is not an official time (so it cannot be used to argue with referees)
+ * @return Match time in seconds since the beginning of autonomous
+ */
+double DriverStation::GetMatchTime()
+{
+ if (m_approxMatchTimeOffset < 0.0)
+ return 0.0;
+ return Timer::GetFPGATimestamp() - m_approxMatchTimeOffset;
+}
+
+/**
+ * Return the team number that the Driver Station is configured for
+ * @return The team number
+ */
+UINT16 DriverStation::GetTeamNumber()
+{
+ return m_controlData->teamID;
+}
diff --git a/aos/externals/WPILib/WPILib/DriverStation.h b/aos/externals/WPILib/WPILib/DriverStation.h
new file mode 100644
index 0000000..94b6956
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DriverStation.h
@@ -0,0 +1,127 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __DRIVER_STATION_H__
+#define __DRIVER_STATION_H__
+
+#include "Dashboard.h"
+#include "DriverStationEnhancedIO.h"
+#include "SensorBase.h"
+#include "Task.h"
+
+struct FRCCommonControlData;
+class AnalogChannel;
+
+/**
+ * Provide access to the network communication data to / from the Driver Station.
+ */
+class DriverStation : public SensorBase
+{
+public:
+ enum Alliance {kRed, kBlue, kInvalid};
+
+ virtual ~DriverStation();
+ static DriverStation *GetInstance();
+
+ static const UINT32 kBatteryModuleNumber = 1;
+ static const UINT32 kBatteryChannel = 8;
+ static const UINT32 kJoystickPorts = 4;
+ static const UINT32 kJoystickAxes = 6;
+
+ float GetStickAxis(UINT32 stick, UINT32 axis);
+ short GetStickButtons(UINT32 stick);
+
+ float GetAnalogIn(UINT32 channel);
+ bool GetDigitalIn(UINT32 channel);
+ void SetDigitalOut(UINT32 channel, bool value);
+ bool GetDigitalOut(UINT32 channel);
+
+ bool IsEnabled();
+ bool IsDisabled();
+ bool IsAutonomous();
+ bool IsOperatorControl();
+ bool IsNewControlData();
+ bool IsFMSAttached();
+
+ UINT32 GetPacketNumber();
+ Alliance GetAlliance();
+ UINT32 GetLocation();
+ void WaitForData();
+ double GetMatchTime();
+ float GetBatteryVoltage();
+ UINT16 GetTeamNumber();
+
+ // Get the default dashboard packers. These instances stay around even after
+ // a call to SetHigh|LowPriorityDashboardPackerToUse() changes which packer
+ // is in use. You can restore the default high priority packer by calling
+ // SetHighPriorityDashboardPackerToUse(&GetHighPriorityDashboardPacker()).
+ Dashboard& GetHighPriorityDashboardPacker() { return m_dashboardHigh; }
+ Dashboard& GetLowPriorityDashboardPacker() { return m_dashboardLow; }
+
+ // Get/set the dashboard packers to use. This can sideline or restore the
+ // default packers. Initializing SmartDashboard changes the high priority
+ // packer in use so beware that the default packer will then be idle. These
+ // methods support any kind of DashboardBase, e.g. a Dashboard or a
+ // SmartDashboard.
+ DashboardBase* GetHighPriorityDashboardPackerInUse() { return m_dashboardInUseHigh; }
+ DashboardBase* GetLowPriorityDashboardPackerInUse() { return m_dashboardInUseLow; }
+ void SetHighPriorityDashboardPackerToUse(DashboardBase* db) { m_dashboardInUseHigh = db; }
+ void SetLowPriorityDashboardPackerToUse(DashboardBase* db) { m_dashboardInUseLow = db; }
+
+ DriverStationEnhancedIO& GetEnhancedIO() { return m_enhancedIO; }
+
+ void IncrementUpdateNumber() { m_updateNumber++; }
+ SEM_ID GetUserStatusDataSem() { return m_statusDataSemaphore; }
+
+ /** Only to be used to tell the Driver Station what code you claim to be executing
+ * for diagnostic purposes only
+ * @param entering If true, starting disabled code; if false, leaving disabled code */
+ void InDisabled(bool entering) {m_userInDisabled=entering;}
+ /** Only to be used to tell the Driver Station what code you claim to be executing
+ * for diagnostic purposes only
+ * @param entering If true, starting autonomous code; if false, leaving autonomous code */
+ void InAutonomous(bool entering) {m_userInAutonomous=entering;}
+ /** Only to be used to tell the Driver Station what code you claim to be executing
+ * for diagnostic purposes only
+ * @param entering If true, starting teleop code; if false, leaving teleop code */
+ void InOperatorControl(bool entering) {m_userInTeleop=entering;}
+
+protected:
+ DriverStation();
+
+ void GetData();
+ void SetData();
+
+private:
+ static void InitTask(DriverStation *ds);
+ static DriverStation *m_instance;
+ static UINT8 m_updateNumber;
+ ///< TODO: Get rid of this and use the semaphore signaling
+ static const float kUpdatePeriod = 0.02;
+
+ void Run();
+
+ struct FRCCommonControlData *m_controlData;
+ UINT8 m_digitalOut;
+ AnalogChannel *m_batteryChannel;
+ SEM_ID m_statusDataSemaphore;
+ Task m_task;
+ Dashboard m_dashboardHigh; // the default dashboard packers
+ Dashboard m_dashboardLow;
+ DashboardBase* m_dashboardInUseHigh; // the current dashboard packers in use
+ DashboardBase* m_dashboardInUseLow;
+ SEM_ID m_newControlData;
+ SEM_ID m_packetDataAvailableSem;
+ DriverStationEnhancedIO m_enhancedIO;
+ SEM_ID m_waitForDataSem;
+ double m_approxMatchTimeOffset;
+ bool m_userInDisabled;
+ bool m_userInAutonomous;
+ bool m_userInTeleop;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/DriverStationEnhancedIO.cpp b/aos/externals/WPILib/WPILib/DriverStationEnhancedIO.cpp
new file mode 100644
index 0000000..5c73453
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DriverStationEnhancedIO.cpp
@@ -0,0 +1,995 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "DriverStationEnhancedIO.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Synchronized.h"
+#include "WPIErrors.h"
+#include <strLib.h>
+
+/**
+ * DriverStationEnhancedIO contructor.
+ *
+ * This is only called once when the DriverStation constructor is called.
+ */
+DriverStationEnhancedIO::DriverStationEnhancedIO()
+ : m_inputValid (false)
+ , m_outputValid (false)
+ , m_configChanged (false)
+ , m_requestEnhancedEnable (false)
+{
+ bzero((char*)&m_inputData, sizeof(m_inputData));
+ bzero((char*)&m_outputData, sizeof(m_outputData));
+ m_outputData.size = sizeof(m_outputData) - 1;
+ m_outputData.id = kOutputBlockID;
+ // Expected to be active low, so initialize inactive.
+ m_outputData.data.fixed_digital_out = 0x3;
+ m_inputDataSemaphore = semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+ m_outputDataSemaphore = semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+ m_encoderOffsets[0] = 0;
+ m_encoderOffsets[1] = 0;
+}
+
+/**
+ * DriverStationEnhancedIO destructor.
+ *
+ * Called only when the DriverStation class is destroyed.
+ */
+DriverStationEnhancedIO::~DriverStationEnhancedIO()
+{
+ semDelete(m_outputDataSemaphore);
+ semDelete(m_inputDataSemaphore);
+}
+
+/**
+ * Called by the DriverStation class when data is available.
+ * This function will set any modified configuration / output,
+ * then read the input and configuration from the IO.
+ */
+void DriverStationEnhancedIO::UpdateData()
+{
+ INT32 retVal;
+ {
+ status_block_t tempOutputData;
+ Synchronized sync(m_outputDataSemaphore);
+ if (m_outputValid || m_configChanged || m_requestEnhancedEnable)
+ {
+ m_outputData.flags = kStatusValid;
+ if (m_requestEnhancedEnable)
+ {
+ // Someone called one of the get config APIs, but we are not in enhanced mode.
+ m_outputData.flags |= kForceEnhancedMode;
+ }
+ if (m_configChanged)
+ {
+ if (!m_outputValid)
+ {
+ // Someone called one of the set config APIs, but we are not in enhanced mode.
+ m_outputData.flags |= kForceEnhancedMode;
+ }
+ m_outputData.flags |= kStatusConfigChanged;
+ }
+ overrideIOConfig((char*)&m_outputData, 5);
+ }
+ retVal = getDynamicControlData(kOutputBlockID, (char*)&tempOutputData, sizeof(status_block_t), 5);
+ if (retVal == 0)
+ {
+ if (m_outputValid)
+ {
+ if (m_configChanged)
+ {
+ // If our config change made the round trip then clear the flag.
+ if (IsConfigEqual(tempOutputData, m_outputData))
+ {
+ m_configChanged = false;
+ }
+ }
+ else
+ {
+ // TODO: This won't work until artf1128 is fixed
+ //if (tempOutputData.flags & kStatusConfigChanged)
+ {
+ // Configuration was updated on the DS, so update our local cache.
+ MergeConfigIntoOutput(tempOutputData, m_outputData);
+ }
+ }
+ }
+ else
+ {
+ // Initialize the local cache.
+ MergeConfigIntoOutput(tempOutputData, m_outputData);
+ }
+ m_requestEnhancedEnable = false;
+ m_outputValid = true;
+ }
+ else
+ {
+ m_outputValid = false;
+ m_inputValid = false;
+ }
+ }
+ {
+ Synchronized sync(m_inputDataSemaphore);
+ control_block_t tempInputData;
+ retVal = getDynamicControlData(kInputBlockID, (char*)&tempInputData, sizeof(control_block_t), 5);
+ if (retVal == 0 && tempInputData.data.api_version == kSupportedAPIVersion)
+ {
+ m_inputData = tempInputData;
+ m_inputValid = true;
+ }
+ else
+ {
+ m_outputValid = false;
+ m_inputValid = false;
+ }
+ }
+}
+
+/**
+ * Merge the config portion of the DS output block into the local cache.
+ */
+void DriverStationEnhancedIO::MergeConfigIntoOutput(const status_block_t &dsOutputBlock, status_block_t &localCache)
+{
+ localCache.data.digital = (localCache.data.digital & dsOutputBlock.data.digital_oe) |
+ (dsOutputBlock.data.digital & ~dsOutputBlock.data.digital_oe);
+ localCache.data.digital_oe = dsOutputBlock.data.digital_oe;
+ localCache.data.digital_pe = dsOutputBlock.data.digital_pe;
+ localCache.data.pwm_period[0] = dsOutputBlock.data.pwm_period[0];
+ localCache.data.pwm_period[1] = dsOutputBlock.data.pwm_period[1];
+ localCache.data.enables = dsOutputBlock.data.enables;
+}
+
+/**
+ * Compare the config portion of the output blocks.
+ */
+bool DriverStationEnhancedIO::IsConfigEqual(const status_block_t &dsOutputBlock, const status_block_t &localCache)
+{
+ if (localCache.data.digital_oe != dsOutputBlock.data.digital_oe) return false;
+ if ((localCache.data.digital & ~dsOutputBlock.data.digital) !=
+ (dsOutputBlock.data.digital & ~dsOutputBlock.data.digital)) return false;
+ if (localCache.data.digital_pe != dsOutputBlock.data.digital_pe) return false;
+ if (localCache.data.pwm_period[0] != dsOutputBlock.data.pwm_period[0]) return false;
+ if (localCache.data.pwm_period[1] != dsOutputBlock.data.pwm_period[1]) return false;
+ if (localCache.data.enables != dsOutputBlock.data.enables) return false;
+ return true;
+}
+
+/**
+ * Query an accelerometer channel on the DS IO.
+ *
+ * @param channel The channel number to read.
+ * @return The current acceleration on the channel in Gs.
+ */
+double DriverStationEnhancedIO::GetAcceleration(tAccelChannel channel)
+{
+ if (channel < 1 || channel > 2)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 2");
+ return 0.0;
+ }
+ if (!m_inputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return 0.0;
+ }
+
+ static UINT8 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, channel, nUsageReporting::kDriverStationEIO_Acceleration);
+ reported_mask |= (1 >> channel);
+ }
+
+ Synchronized sync(m_inputDataSemaphore);
+ return (m_inputData.data.accel[channel] - kAccelOffset) / kAccelScale;
+}
+
+/**
+ * Query an analog input channel on the DS IO.
+ *
+ * @param channel The channel number to read. [1,8]
+ * @return The analog input voltage for the channel.
+ */
+double DriverStationEnhancedIO::GetAnalogIn(UINT32 channel)
+{
+ // 3.3V is the analog reference voltage
+ return GetAnalogInRatio(channel) * kAnalogInputReference;
+}
+
+/**
+ * Query an analog input channel on the DS IO in ratiometric form.
+ *
+ * @param channel The channel number to read. [1,8]
+ * @return The analog input percentage for the channel.
+ */
+double DriverStationEnhancedIO::GetAnalogInRatio(UINT32 channel)
+{
+ if (channel < 1 || channel > 8)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 8");
+ return 0.0;
+ }
+ if (!m_inputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return 0.0;
+ }
+
+ static UINT16 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, channel, nUsageReporting::kDriverStationEIO_AnalogIn);
+ reported_mask |= (1 >> channel);
+ }
+
+ Synchronized sync(m_inputDataSemaphore);
+ return m_inputData.data.analog[channel-1] / kAnalogInputResolution;
+}
+
+/**
+ * Query the voltage currently being output.
+ *
+ * AO1 is pin 11 on the top connector (P2).
+ * AO2 is pin 12 on the top connector (P2).
+ *
+ * @param channel The analog output channel on the DS IO. [1,2]
+ * @return The voltage being output on the channel.
+ */
+double DriverStationEnhancedIO::GetAnalogOut(UINT32 channel)
+{
+ if (channel < 1 || channel > 2)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 2");
+ return 0.0;
+ }
+ if (!m_outputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return 0.0;
+ }
+
+ Synchronized sync(m_outputDataSemaphore);
+ return m_outputData.data.dac[channel-1] * kAnalogOutputReference / kAnalogOutputResolution;
+}
+
+/**
+ * Set the analog output voltage.
+ *
+ * AO1 is pin 11 on the top connector (P2).
+ * AO2 is pin 12 on the top connector (P2).
+ * AO1 is the reference voltage for the 2 analog comparators on DIO15 and DIO16.
+ *
+ * The output range is 0V to 4V, however due to the supply voltage don't expect more than about 3V.
+ * Current supply capability is only 100uA.
+ *
+ * @param channel The analog output channel on the DS IO. [1,2]
+ * @param value The voltage to output on the channel.
+ */
+void DriverStationEnhancedIO::SetAnalogOut(UINT32 channel, double value)
+{
+ if (channel < 1 || channel > 2)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 2");
+ return;
+ }
+ if (!m_outputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return;
+ }
+ if (value < 0.0) value = 0.0;
+ if (value > kAnalogOutputReference) value = kAnalogOutputReference;
+
+ static UINT8 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, channel, nUsageReporting::kDriverStationEIO_AnalogOut);
+ reported_mask |= (1 >> channel);
+ }
+
+ Synchronized sync(m_outputDataSemaphore);
+ m_outputData.data.dac[channel-1] = (UINT8)(value / kAnalogOutputReference * kAnalogOutputResolution);
+}
+
+/**
+ * Get the state of a button on the IO board.
+ *
+ * Button1 is the physical button "S1".
+ * Button2 is pin 4 on the top connector (P2).
+ * Button3 is pin 6 on the top connector (P2).
+ * Button4 is pin 8 on the top connector (P2).
+ * Button5 is pin 10 on the top connector (P2).
+ * Button6 is pin 7 on the top connector (P2).
+ *
+ * Button2 through Button6 are Capacitive Sense buttons.
+ *
+ * @param channel The button channel to read. [1,6]
+ * @return The state of the selected button.
+ */
+bool DriverStationEnhancedIO::GetButton(UINT32 channel)
+{
+ if (channel < 1 || channel > 6)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 6");
+ return false;
+ }
+
+ static UINT8 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, channel, nUsageReporting::kDriverStationEIO_Button);
+ reported_mask |= (1 >> channel);
+ }
+
+ return ((GetButtons() >> (channel-1)) & 1) != 0;
+}
+
+/**
+ * Get the state of all the button channels.
+ *
+ * @return The state of the 6 button channels in the 6 lsb of the returned byte.
+ */
+UINT8 DriverStationEnhancedIO::GetButtons()
+{
+ if (!m_inputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return 0;
+ }
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, 0, nUsageReporting::kDriverStationEIO_Button);
+ Synchronized sync(m_inputDataSemaphore);
+ return m_inputData.data.buttons;
+}
+
+/**
+ * Set the state of an LED on the IO board.
+ *
+ * @param channel The LED channel to set. [1,8]
+ * @param value True to turn the LED on.
+ */
+void DriverStationEnhancedIO::SetLED(UINT32 channel, bool value)
+{
+ if (channel < 1 || channel > 8)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 8");
+ return;
+ }
+ if (!m_outputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return;
+ }
+
+ static UINT16 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, channel, nUsageReporting::kDriverStationEIO_LED);
+ reported_mask |= (1 >> channel);
+ }
+
+ UINT8 leds;
+ Synchronized sync(m_outputDataSemaphore);
+ leds = m_outputData.data.leds;
+
+ leds &= ~(1 << (channel-1));
+ if (value) leds |= 1 << (channel-1);
+
+ m_outputData.data.leds = leds;
+}
+
+/**
+ * Set the state of all 8 LEDs on the IO board.
+ *
+ * @param value The state of each LED. LED1 is lsb and LED8 is msb.
+ */
+void DriverStationEnhancedIO::SetLEDs(UINT8 value)
+{
+ if (!m_outputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return;
+ }
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, 0, nUsageReporting::kDriverStationEIO_LED);
+ Synchronized sync(m_outputDataSemaphore);
+ m_outputData.data.leds = value;
+}
+
+/**
+ * Get the current state of a DIO channel regardless of mode.
+ *
+ * @param channel The DIO channel to read. [1,16]
+ * @return The state of the selected digital line.
+ */
+bool DriverStationEnhancedIO::GetDigital(UINT32 channel)
+{
+ if (channel < 1 || channel > 16)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 16");
+ return false;
+ }
+
+ static UINT32 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, channel, nUsageReporting::kDriverStationEIO_DigitalIn);
+ reported_mask |= (1 >> channel);
+ }
+
+ return ((GetDigitals() >> (channel-1)) & 1) != 0;
+}
+
+/**
+ * Get the state of all 16 DIO lines regardless of mode.
+ *
+ * @return The state of all DIO lines. DIO1 is lsb and DIO16 is msb.
+ */
+UINT16 DriverStationEnhancedIO::GetDigitals()
+{
+ if (!m_inputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return 0;
+ }
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, 0, nUsageReporting::kDriverStationEIO_DigitalIn);
+ Synchronized sync(m_inputDataSemaphore);
+ return m_inputData.data.digital;
+}
+
+/**
+ * Set the state of a DIO line that is configured for digital output.
+ *
+ * @param channel The DIO channel to set. [1,16]
+ * @param value The state to set the selected channel to.
+ */
+void DriverStationEnhancedIO::SetDigitalOutput(UINT32 channel, bool value)
+{
+ if (channel < 1 || channel > 16)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 16");
+ return;
+ }
+ if (!m_outputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return;
+ }
+
+ static UINT32 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, channel, nUsageReporting::kDriverStationEIO_DigitalOut);
+ reported_mask |= (1 >> channel);
+ }
+
+ UINT16 digital;
+ Synchronized sync(m_outputDataSemaphore);
+
+ if (m_outputData.data.digital_oe & (1 << (channel-1)))
+ {
+ digital = m_outputData.data.digital;
+
+ digital &= ~(1 << (channel-1));
+ if (value) digital |= 1 << (channel-1);
+
+ m_outputData.data.digital = digital;
+ }
+ else
+ {
+ wpi_setWPIError(LineNotOutput);
+ }
+}
+
+/**
+ * Get the current configuration for a DIO line.
+ *
+ * This has the side effect of forcing the Driver Station to switch to Enhanced mode if it's not when called.
+ * If Enhanced mode is not enabled when this is called, it will return kUnknown.
+ *
+ * @param channel The DIO channel config to get. [1,16]
+ * @return The configured mode for the DIO line.
+ */
+DriverStationEnhancedIO::tDigitalConfig DriverStationEnhancedIO::GetDigitalConfig(UINT32 channel)
+{
+ if (channel < 1 || channel > 16)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 16");
+ return kUnknown;
+ }
+ if (!m_outputValid)
+ {
+ m_requestEnhancedEnable = true;
+ wpi_setWPIError(EnhancedIOMissing);
+ return kUnknown;
+ }
+ Synchronized sync(m_outputDataSemaphore);
+ if ((channel >= 1) && (channel <= 4))
+ {
+ if (m_outputData.data.pwm_enable & (1 << (channel - 1)))
+ {
+ return kPWM;
+ }
+ }
+ if ((channel >= 15) && (channel <= 16))
+ {
+ if (m_outputData.data.comparator_enable & (1 << (channel - 15)))
+ {
+ return kAnalogComparator;
+ }
+ }
+ if (m_outputData.data.digital_oe & (1 << (channel - 1)))
+ {
+ return kOutput;
+ }
+ if (!(m_outputData.data.digital_pe & (1 << (channel - 1))))
+ {
+ return kInputFloating;
+ }
+ if (m_outputData.data.digital & (1 << (channel - 1)))
+ {
+ return kInputPullUp;
+ }
+ else
+ {
+ return kInputPullDown;
+ }
+}
+
+/**
+ * Override the DS's configuration of a DIO line.
+ *
+ * If configured to kInputFloating, the selected DIO line will be tri-stated with no internal pull resistor.
+ *
+ * If configured to kInputPullUp, the selected DIO line will be tri-stated with a 5k-Ohm internal pull-up resistor enabled.
+ *
+ * If configured to kInputPullDown, the selected DIO line will be tri-stated with a 5k-Ohm internal pull-down resistor enabled.
+ *
+ * If configured to kOutput, the selected DIO line will actively drive to 0V or Vddio (specified by J1 and J4).
+ * DIO1 through DIO12, DIO15, and DIO16 can source 4mA and can sink 8mA.
+ * DIO12 and DIO13 can source 4mA and can sink 25mA.
+ *
+ * In addition to the common configurations, DIO1 through DIO4 can be configured to kPWM to enable PWM output.
+ *
+ * In addition to the common configurations, DIO15 and DIO16 can be configured to kAnalogComparator to enable
+ * analog comparators on those 2 DIO lines. When enabled, the lines are tri-stated and will accept analog voltages
+ * between 0V and 3.3V. If the input voltage is greater than the voltage output by AO1, the DIO will read as true,
+ * if less then false.
+ *
+ * @param channel The DIO line to configure. [1,16]
+ * @param config The mode to put the DIO line in.
+ */
+void DriverStationEnhancedIO::SetDigitalConfig(UINT32 channel, tDigitalConfig config)
+{
+ if (channel < 1 || channel > 16)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 16");
+ return;
+ }
+ if (config == kPWM && (channel < 1 || channel > 4))
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel in PWM mode must be between 1 and 4");
+ return;
+ }
+ if (config == kAnalogComparator && (channel < 15 || channel > 16))
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel in Analog Comparator mode must be between 15 and 16");
+ return;
+ }
+
+ Synchronized sync(m_outputDataSemaphore);
+ m_configChanged = true;
+
+ if ((channel >= 1) && (channel <= 4))
+ {
+ if (config == kPWM)
+ {
+ m_outputData.data.pwm_enable |= 1 << (channel - 1);
+ m_outputData.data.digital &= ~(1 << (channel - 1));
+ m_outputData.data.digital_oe |= 1 << (channel - 1);
+ m_outputData.data.digital_pe &= ~(1 << (channel - 1));
+ return;
+ }
+ else
+ {
+ m_outputData.data.pwm_enable &= ~(1 << (channel - 1));
+ }
+ }
+ else if ((channel >= 15) && (channel <= 16))
+ {
+ if (config == kAnalogComparator)
+ {
+ m_outputData.data.comparator_enable |= 1 << (channel - 15);
+ m_outputData.data.digital &= ~(1 << (channel - 1));
+ m_outputData.data.digital_oe &= ~(1 << (channel - 1));
+ m_outputData.data.digital_pe &= ~(1 << (channel - 1));
+ return;
+ }
+ else
+ {
+ m_outputData.data.comparator_enable &= ~(1 << (channel - 15));
+ }
+ }
+ if (config == kInputFloating)
+ {
+ m_outputData.data.digital &= ~(1 << (channel - 1));
+ m_outputData.data.digital_oe &= ~(1 << (channel - 1));
+ m_outputData.data.digital_pe &= ~(1 << (channel - 1));
+ }
+ else if (config == kInputPullUp)
+ {
+ m_outputData.data.digital |= 1 << (channel - 1);
+ m_outputData.data.digital_oe &= ~(1 << (channel - 1));
+ m_outputData.data.digital_pe |= 1 << (channel - 1);
+ }
+ else if (config == kInputPullDown)
+ {
+ m_outputData.data.digital &= ~(1 << (channel - 1));
+ m_outputData.data.digital_oe &= ~(1 << (channel - 1));
+ m_outputData.data.digital_pe |= 1 << (channel - 1);
+ }
+ else if (config == kOutput)
+ {
+ m_outputData.data.digital_oe |= 1 << (channel - 1);
+ m_outputData.data.digital_pe &= ~(1 << (channel - 1));
+ }
+ else
+ {
+ // Something went wrong.
+ }
+}
+
+/**
+ * Get the period of a PWM generator.
+ *
+ * This has the side effect of forcing the Driver Station to switch to Enhanced mode if it's not when called.
+ * If Enhanced mode is not enabled when this is called, it will return 0.
+ *
+ * @param channels Select the generator by specifying the two channels to which it is connected.
+ * @return The period of the PWM generator in seconds.
+ */
+double DriverStationEnhancedIO::GetPWMPeriod(tPWMPeriodChannels channels)
+{
+ if (channels < kPWMChannels1and2 || channels > kPWMChannels3and4)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channels must be kPWMChannels1and2 or kPWMChannels3and4");
+ return 0.0;
+ }
+ if (!m_outputValid)
+ {
+ m_requestEnhancedEnable = true;
+ wpi_setWPIError(EnhancedIOMissing);
+ return 0.0;
+ }
+
+ Synchronized sync(m_outputDataSemaphore);
+ return m_outputData.data.pwm_period[channels] / 24000000.0;
+}
+
+/**
+ * Set the period of a PWM generator.
+ *
+ * There are 2 PWM generators on the IO board. One can generate PWM signals on DIO1 and DIO2,
+ * the other on DIO3 and DIO4. Each generator has one counter and two compare registers. As such,
+ * each pair of PWM outputs share the output period but have independent duty cycles.
+ *
+ * @param channels Select the generator by specifying the two channels to which it is connected.
+ * @param period The period of the PWM generator in seconds. [0.0,0.002731]
+ */
+void DriverStationEnhancedIO::SetPWMPeriod(tPWMPeriodChannels channels, double period)
+{
+ if (channels < kPWMChannels1and2 || channels > kPWMChannels3and4)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channels must be kPWMChannels1and2 or kPWMChannels3and4");
+ return;
+ }
+
+ // Convert to ticks based on the IO board's 24MHz clock
+ double ticks = period * 24000000.0;
+ // Limit the range of the ticks... warn if too big.
+ if (ticks > 65534.0)
+ {
+ wpi_setWPIError(EnhancedIOPWMPeriodOutOfRange);
+ ticks = 65534.0;
+ }
+ else if (ticks < 0.0) ticks = 0.0;
+ // Preserve the duty cycles.
+ double dutyCycles[2];
+ dutyCycles[0] = GetPWMOutput((channels << 1) + 1);
+ dutyCycles[1] = GetPWMOutput((channels << 1) + 2);
+ {
+ Synchronized sync(m_outputDataSemaphore);
+ // Update the period
+ m_outputData.data.pwm_period[channels] = (UINT16)ticks;
+ m_configChanged = true;
+ }
+ // Restore the duty cycles
+ SetPWMOutput((channels << 1) + 1, dutyCycles[0]);
+ SetPWMOutput((channels << 1) + 2, dutyCycles[1]);
+}
+
+/**
+ * Get the state being output on a fixed digital output.
+ *
+ * @param channel The FixedDO line to get. [1,2]
+ * @return The state of the FixedDO line.
+ */
+bool DriverStationEnhancedIO::GetFixedDigitalOutput(UINT32 channel)
+{
+ if (channel < 1 || channel > 2)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 2");
+ return 0;
+ }
+ if (!m_outputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return 0;
+ }
+
+ Synchronized sync(m_outputDataSemaphore);
+ return ((m_outputData.data.fixed_digital_out >> (channel-1)) & 1) != 0;
+}
+
+/**
+ * Set the state to output on a Fixed High Current Digital Output line.
+ *
+ * FixedDO1 is pin 5 on the top connector (P2).
+ * FixedDO2 is pin 3 on the top connector (P2).
+ *
+ * The FixedDO lines always output 0V and 3.3V regardless of J1 and J4.
+ * They can source 4mA and can sink 25mA. Because of this, they are expected to be used
+ * in an active low configuration, such as connecting to the cathode of a bright LED.
+ * Because they are expected to be active low, they default to true.
+ *
+ * @param channel The FixedDO channel to set.
+ * @param value The state to set the FixedDO.
+ */
+void DriverStationEnhancedIO::SetFixedDigitalOutput(UINT32 channel, bool value)
+{
+ if (channel < 1 || channel > 2)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 2");
+ return;
+ }
+ if (!m_outputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return;
+ }
+
+ static UINT8 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, channel, nUsageReporting::kDriverStationEIO_FixedDigitalOut);
+ reported_mask |= (1 >> channel);
+ }
+
+ UINT8 digital;
+ Synchronized sync(m_outputDataSemaphore);
+ digital = m_outputData.data.fixed_digital_out;
+
+ digital &= ~(1 << (channel-1));
+ if (value) digital |= 1 << (channel-1);
+
+ m_outputData.data.fixed_digital_out = digital;
+}
+
+/**
+ * Get the position of a quadrature encoder.
+ *
+ * There are two signed 16-bit 4X quadrature decoders on the IO board. These decoders are always monitoring
+ * the state of the lines assigned to them, but these lines do not have to be used for encoders.
+ *
+ * Encoder1 uses DIO4 for "A", DIO6 for "B", and DIO8 for "Index".
+ * Encoder2 uses DIO5 for "A", DIO7 for "B", and DIO9 for "Index".
+ *
+ * The index functionality can be enabled or disabled using SetEncoderIndexEnable().
+ *
+ * @param encoderNumber The quadrature encoder to access. [1,2]
+ * @return The current position of the quadrature encoder.
+ */
+INT16 DriverStationEnhancedIO::GetEncoder(UINT32 encoderNumber)
+{
+ if (encoderNumber < 1 || encoderNumber > 2)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "encoderNumber must be between 1 and 2");
+ return 0;
+ }
+ if (!m_inputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return 0;
+ }
+
+ static UINT8 reported_mask = 0;
+ if (!(reported_mask & (1 >> encoderNumber)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, encoderNumber, nUsageReporting::kDriverStationEIO_Encoder);
+ reported_mask |= (1 >> encoderNumber);
+ }
+
+ Synchronized sync(m_inputDataSemaphore);
+ return m_inputData.data.quad[encoderNumber - 1] - m_encoderOffsets[encoderNumber - 1];
+}
+
+/**
+ * Reset the position of an encoder to 0.
+ *
+ * This simply stores an offset locally. It does not reset the hardware counter on the IO board.
+ * If you use this method with Index enabled, you may get unexpected results.
+ *
+ * @param encoderNumber The quadrature encoder to reset. [1,2]
+ */
+void DriverStationEnhancedIO::ResetEncoder(UINT32 encoderNumber)
+{
+ if (encoderNumber < 1 || encoderNumber > 2)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "encoderNumber must be between 1 and 2");
+ return;
+ }
+ if (!m_inputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return;
+ }
+
+ Synchronized sync(m_inputDataSemaphore);
+ m_encoderOffsets[encoderNumber - 1] = m_inputData.data.quad[encoderNumber - 1];
+}
+
+/**
+ * Get the current configuration of a quadrature encoder index channel.
+ *
+ * This has the side effect of forcing the Driver Station to switch to Enhanced mode if it's not when called.
+ * If Enhanced mode is not enabled when this is called, it will return false.
+ *
+ * @param encoderNumber The quadrature encoder. [1,2]
+ * @return Is the index channel of the encoder enabled.
+ */
+bool DriverStationEnhancedIO::GetEncoderIndexEnable(UINT32 encoderNumber)
+{
+ if (encoderNumber < 1 || encoderNumber > 2)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "encoderNumber must be between 1 and 2");
+ return false;
+ }
+ if (!m_outputValid)
+ {
+ m_requestEnhancedEnable = true;
+ wpi_setWPIError(EnhancedIOMissing);
+ return false;
+ }
+
+ Synchronized sync(m_outputDataSemaphore);
+ return ((m_outputData.data.quad_index_enable >> (encoderNumber - 1)) & 1) != 0;
+}
+
+/**
+ * Enable or disable the index channel of a quadrature encoder.
+ *
+ * The quadrature decoders on the IO board support an active-low index input.
+ *
+ * Encoder1 uses DIO8 for "Index".
+ * Encoder2 uses DIO9 for "Index".
+ *
+ * When enabled, the decoder's counter will be reset to 0 when A, B, and Index are all low.
+ *
+ * @param encoderNumber The quadrature encoder. [1,2]
+ * @param enable If true, reset the encoder in an index condition.
+ */
+void DriverStationEnhancedIO::SetEncoderIndexEnable(UINT32 encoderNumber, bool enable)
+{
+ if (encoderNumber < 1 || encoderNumber > 2)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "encoderNumber must be between 1 and 2");
+ return;
+ }
+
+ Synchronized sync(m_outputDataSemaphore);
+ m_outputData.data.quad_index_enable &= ~(1 << (encoderNumber - 1));
+ if (enable) m_outputData.data.quad_index_enable |= 1 << (encoderNumber - 1);
+ m_configChanged = true;
+}
+
+/**
+ * Get the value of the Capacitive Sense touch slider.
+ *
+ * @return Value between 0.0 (toward center of board) and 1.0 (toward edge of board). -1.0 means no touch detected.
+ */
+double DriverStationEnhancedIO::GetTouchSlider()
+{
+ if (!m_inputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return 0.0;
+ }
+
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, 1, nUsageReporting::kDriverStationEIO_TouchSlider);
+
+ Synchronized sync(m_inputDataSemaphore);
+ UINT8 value = m_inputData.data.capsense_slider;
+ return value == 255 ? -1.0 : value / 254.0;
+}
+
+/**
+ * Get the percent duty-cycle that the PWM generator channel is configured to output.
+ *
+ * @param channel The DIO line's PWM generator to get the duty-cycle from. [1,4]
+ * @return The percent duty-cycle being output (if the DIO line is configured for PWM). [0.0,1.0]
+ */
+double DriverStationEnhancedIO::GetPWMOutput(UINT32 channel)
+{
+ if (channel < 1 || channel > 4)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 4");
+ return 0.0;
+ }
+ if (!m_outputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return 0.0;
+ }
+
+ Synchronized sync(m_outputDataSemaphore);
+ return (double)m_outputData.data.pwm_compare[channel - 1] / (double)m_outputData.data.pwm_period[(channel - 1) >> 1];
+}
+
+/**
+ * Set the percent duty-cycle to output on a PWM enabled DIO line.
+ *
+ * DIO1 through DIO4 have the ability to output a PWM signal. The period of the
+ * signal can be configured in pairs using SetPWMPeriod().
+ *
+ * @param channel The DIO line's PWM generator to set. [1,4]
+ * @param value The percent duty-cycle to output from the PWM generator. [0.0,1.0]
+ */
+void DriverStationEnhancedIO::SetPWMOutput(UINT32 channel, double value)
+{
+ if (channel < 1 || channel > 4)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 4");
+ return;
+ }
+ if (!m_outputValid)
+ {
+ wpi_setWPIError(EnhancedIOMissing);
+ return;
+ }
+
+ static UINT8 reported_mask = 0;
+ if (!(reported_mask & (1 >> channel)))
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationEIO, channel, nUsageReporting::kDriverStationEIO_PWM);
+ reported_mask |= (1 >> channel);
+ }
+
+ if (value > 1.0) value = 1.0;
+ else if (value < 0.0) value = 0.0;
+ Synchronized sync(m_outputDataSemaphore);
+ m_outputData.data.pwm_compare[channel - 1] = (UINT16)(value * (double)m_outputData.data.pwm_period[(channel - 1) >> 1]);
+}
+
+/**
+ * Get the firmware version running on the IO board.
+ *
+ * This also has the side effect of forcing the driver station to switch to Enhanced mode if it is not.
+ * If you plan to switch between Driver Stations with unknown IO configurations, you can call this
+ * until it returns a non-0 version to ensure that this API is accessible before proceeding.
+ *
+ * @return The version of the firmware running on the IO board. 0 if the board is not attached or not in Enhanced mode.
+ */
+UINT8 DriverStationEnhancedIO::GetFirmwareVersion()
+{
+ if (!m_inputValid)
+ {
+ m_requestEnhancedEnable = true;
+ wpi_setWPIError(EnhancedIOMissing);
+ return 0;
+ }
+
+ Synchronized sync(m_inputDataSemaphore);
+ return m_inputData.data.fw_version;
+}
+
diff --git a/aos/externals/WPILib/WPILib/DriverStationEnhancedIO.h b/aos/externals/WPILib/WPILib/DriverStationEnhancedIO.h
new file mode 100644
index 0000000..fda32b8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DriverStationEnhancedIO.h
@@ -0,0 +1,151 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __DRIVER_STATION_ENHANCED_IO_H__
+#define __DRIVER_STATION_ENHANCED_IO_H__
+
+#include "ErrorBase.h"
+#include "NetworkCommunication/FRCComm.h"
+#include <stack>
+#include <vector>
+#include <vxWorks.h>
+
+#define kAnalogInputResolution ((double)((1<<14)-1))
+#define kAnalogInputReference 3.3
+#define kAnalogOutputResolution ((double)((1<<8)-1))
+#define kAnalogOutputReference 4.0
+#define kAccelOffset 8300
+#define kAccelScale 3300.0
+#define kSupportedAPIVersion 1
+
+/**
+ * Interact with the more complete I/O available from the
+ * newest driver station. Get a reference to an object
+ * of this type by calling GetEnhancedIO() on the DriverStation object.
+ */
+class DriverStationEnhancedIO : public ErrorBase
+{
+ // Can only be constructed by the DriverStation class.
+ friend class DriverStation;
+
+#pragma pack(push,1)
+ // BEGIN: Definitions from the Cypress firmware
+ typedef struct
+ {
+ UINT16 digital;
+ UINT16 digital_oe;
+ UINT16 digital_pe;
+ UINT16 pwm_compare[4];
+ UINT16 pwm_period[2];
+ UINT8 dac[2];
+ UINT8 leds;
+ union
+ {
+ struct
+ {
+ // Bits are inverted from cypress fw because of big-endian!
+ UINT8 pwm_enable : 4;
+ UINT8 comparator_enable : 2;
+ UINT8 quad_index_enable : 2;
+ };
+ UINT8 enables;
+ };
+ UINT8 fixed_digital_out;
+ } output_t; //data to IO (23 bytes)
+
+ typedef struct
+ {
+ UINT8 api_version;
+ UINT8 fw_version;
+ INT16 analog[8];
+ UINT16 digital;
+ INT16 accel[3];
+ INT16 quad[2];
+ UINT8 buttons;
+ UINT8 capsense_slider;
+ UINT8 capsense_proximity;
+ } input_t; //data from IO (33 bytes)
+ // END: Definitions from the Cypress firmware
+
+ // Dynamic block definitions
+ typedef struct
+ {
+ UINT8 size; // Must be 25 (size remaining in the block not counting the size variable)
+ UINT8 id; // Must be 18
+ output_t data;
+ UINT8 flags;
+ } status_block_t;
+
+ typedef struct
+ {
+ UINT8 size; // Must be 34
+ UINT8 id; // Must be 17
+ input_t data;
+ } control_block_t;
+#pragma pack(pop)
+
+ enum tBlockID
+ {
+ kInputBlockID = kFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Input,
+ kOutputBlockID = kFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Output,
+ };
+ enum tStatusFlags {kStatusValid = 0x01, kStatusConfigChanged = 0x02, kForceEnhancedMode = 0x04};
+
+public:
+ enum tDigitalConfig {kUnknown, kInputFloating, kInputPullUp, kInputPullDown, kOutput, kPWM, kAnalogComparator};
+ enum tAccelChannel {kAccelX = 0, kAccelY = 1, kAccelZ = 2};
+ enum tPWMPeriodChannels {kPWMChannels1and2, kPWMChannels3and4};
+
+ double GetAcceleration(tAccelChannel channel);
+ double GetAnalogIn(UINT32 channel);
+ double GetAnalogInRatio(UINT32 channel);
+ double GetAnalogOut(UINT32 channel);
+ void SetAnalogOut(UINT32 channel, double value);
+ bool GetButton(UINT32 channel);
+ UINT8 GetButtons();
+ void SetLED(UINT32 channel, bool value);
+ void SetLEDs(UINT8 value);
+ bool GetDigital(UINT32 channel);
+ UINT16 GetDigitals();
+ void SetDigitalOutput(UINT32 channel, bool value);
+ tDigitalConfig GetDigitalConfig(UINT32 channel);
+ void SetDigitalConfig(UINT32 channel, tDigitalConfig config);
+ double GetPWMPeriod(tPWMPeriodChannels channels);
+ void SetPWMPeriod(tPWMPeriodChannels channels, double period);
+ bool GetFixedDigitalOutput(UINT32 channel);
+ void SetFixedDigitalOutput(UINT32 channel, bool value);
+ INT16 GetEncoder(UINT32 encoderNumber);
+ void ResetEncoder(UINT32 encoderNumber);
+ bool GetEncoderIndexEnable(UINT32 encoderNumber);
+ void SetEncoderIndexEnable(UINT32 encoderNumber, bool enable);
+ double GetTouchSlider();
+ double GetPWMOutput(UINT32 channel);
+ void SetPWMOutput(UINT32 channel, double value);
+ UINT8 GetFirmwareVersion();
+
+private:
+ DriverStationEnhancedIO();
+ virtual ~DriverStationEnhancedIO();
+ void UpdateData();
+ void MergeConfigIntoOutput(const status_block_t &dsOutputBlock, status_block_t &localCache);
+ bool IsConfigEqual(const status_block_t &dsOutputBlock, const status_block_t &localCache);
+
+ // Usage Guidelines...
+ DISALLOW_COPY_AND_ASSIGN(DriverStationEnhancedIO);
+
+ control_block_t m_inputData;
+ status_block_t m_outputData;
+ SEM_ID m_inputDataSemaphore;
+ SEM_ID m_outputDataSemaphore;
+ bool m_inputValid;
+ bool m_outputValid;
+ bool m_configChanged;
+ bool m_requestEnhancedEnable;
+ INT16 m_encoderOffsets[2];
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/DriverStationLCD.cpp b/aos/externals/WPILib/WPILib/DriverStationLCD.cpp
new file mode 100644
index 0000000..1a5169a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DriverStationLCD.cpp
@@ -0,0 +1,163 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "DriverStationLCD.h"
+#include "NetworkCommunication/FRCComm.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Synchronized.h"
+#include "WPIErrors.h"
+#include <strLib.h>
+
+const UINT32 DriverStationLCD::kSyncTimeout_ms;
+const UINT16 DriverStationLCD::kFullDisplayTextCommand;
+const INT32 DriverStationLCD::kLineLength;
+const INT32 DriverStationLCD::kNumLines;
+DriverStationLCD* DriverStationLCD::m_instance = NULL;
+
+/**
+ * DriverStationLCD contructor.
+ *
+ * This is only called once the first time GetInstance() is called
+ */
+DriverStationLCD::DriverStationLCD()
+ : m_textBuffer (NULL)
+ , m_textBufferSemaphore (NULL)
+{
+ m_textBuffer = new char[USER_DS_LCD_DATA_SIZE];
+ memset(m_textBuffer, ' ', USER_DS_LCD_DATA_SIZE);
+
+ *((UINT16 *)m_textBuffer) = kFullDisplayTextCommand;
+
+ m_textBufferSemaphore = semMCreate(SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_DriverStationLCD, 0);
+
+ AddToSingletonList();
+}
+
+DriverStationLCD::~DriverStationLCD()
+{
+ semDelete(m_textBufferSemaphore);
+ delete [] m_textBuffer;
+ m_instance = NULL;
+}
+
+/**
+ * Return a pointer to the singleton DriverStationLCD.
+ */
+DriverStationLCD* DriverStationLCD::GetInstance()
+{
+ if (m_instance == NULL)
+ {
+ m_instance = new DriverStationLCD();
+ }
+ return m_instance;
+}
+
+/**
+ * Send the text data to the Driver Station.
+ */
+void DriverStationLCD::UpdateLCD()
+{
+ Synchronized sync(m_textBufferSemaphore);
+ setUserDsLcdData(m_textBuffer, USER_DS_LCD_DATA_SIZE, kSyncTimeout_ms);
+}
+
+/**
+ * Print formatted text to the Driver Station LCD text bufer.
+ *
+ * Use UpdateLCD() periodically to actually send the test to the Driver Station.
+ *
+ * @param line The line on the LCD to print to.
+ * @param startingColumn The column to start printing to. This is a 1-based number.
+ * @param writeFmt The printf format string describing how to print.
+ */
+void DriverStationLCD::Printf(Line line, INT32 startingColumn, const char *writeFmt, ...)
+{
+ va_list args;
+ va_start (args, writeFmt);
+ VPrintf(line, startingColumn, writeFmt, args);
+ va_end (args);
+}
+void DriverStationLCD::VPrintf(Line line, INT32 startingColumn, const char *writeFmt, va_list args)
+{
+ UINT32 start = startingColumn - 1;
+ INT32 maxLength = kLineLength - start;
+ char lineBuffer[kLineLength + 1];
+
+ if (startingColumn < 1 || startingColumn > kLineLength)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "startingColumn");
+ return;
+ }
+
+ if (line < kMain_Line6 || line > kUser_Line6)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "line");
+ return;
+ }
+
+ {
+ Synchronized sync(m_textBufferSemaphore);
+ // snprintf appends NULL to its output. Therefore we can't write directly to the buffer.
+ INT32 length = vsnprintf(lineBuffer, kLineLength + 1, writeFmt, args);
+ if (length < 0) length = kLineLength;
+
+ memcpy(m_textBuffer + start + line * kLineLength + sizeof(UINT16), lineBuffer, std::min(maxLength,length));
+ }
+}
+
+/**
+ * Print formatted text to the Driver Station LCD text bufer. This function
+ * pads the line with empty spaces.
+ *
+ * Use UpdateLCD() periodically to actually send the test to the Driver Station.
+ *
+ * @param line The line on the LCD to print to.
+ * @param writeFmt The printf format string describing how to print.
+ */
+void DriverStationLCD::PrintfLine(Line line, const char *writeFmt, ...)
+{
+ va_list args;
+ va_start (args, writeFmt);
+ VPrintfLine(line, writeFmt, args);
+ va_end (args);
+}
+void DriverStationLCD::VPrintfLine(Line line, const char *writeFmt, va_list args)
+{
+ char lineBuffer[kLineLength + 1];
+
+ if (line < kMain_Line6 || line > kUser_Line6)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "line");
+ return;
+ }
+
+ {
+ Synchronized sync(m_textBufferSemaphore);
+ // snprintf appends NULL to its output. Therefore we can't write directly to the buffer.
+ INT32 length = std::min(vsnprintf(lineBuffer, kLineLength + 1, writeFmt, args), kLineLength);
+ if (length < 0) length = kLineLength;
+
+ // Fill the rest of the buffer
+ if (length < kLineLength)
+ {
+ memset(lineBuffer + length, ' ', kLineLength - length);
+ }
+
+ memcpy(m_textBuffer + line * kLineLength + sizeof(UINT16), lineBuffer, kLineLength);
+ }
+}
+
+/**
+ * Clear all lines on the LCD.
+ */
+void DriverStationLCD::Clear()
+{
+ Synchronized sync(m_textBufferSemaphore);
+ memset(m_textBuffer + sizeof(UINT16), ' ', kLineLength*kNumLines);
+}
+
diff --git a/aos/externals/WPILib/WPILib/DriverStationLCD.h b/aos/externals/WPILib/WPILib/DriverStationLCD.h
new file mode 100644
index 0000000..60a06ad
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/DriverStationLCD.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __DRIVER_STATION_LCD_H__
+#define __DRIVER_STATION_LCD_H__
+
+#include "SensorBase.h"
+
+/**
+ * Provide access to LCD on the Driver Station.
+ *
+ * Buffer the printed data locally and then send it
+ * when UpdateLCD is called.
+ */
+class DriverStationLCD : public SensorBase
+{
+public:
+ static const UINT32 kSyncTimeout_ms = 20;
+ static const UINT16 kFullDisplayTextCommand = 0x9FFF;
+ static const INT32 kLineLength = 21;
+ static const INT32 kNumLines = 6;
+ enum Line {kMain_Line6=0, kUser_Line1=0, kUser_Line2=1, kUser_Line3=2, kUser_Line4=3, kUser_Line5=4, kUser_Line6=5};
+
+ virtual ~DriverStationLCD();
+ static DriverStationLCD *GetInstance();
+
+ void UpdateLCD();
+ void VPrintf(Line line, INT32 startingColumn, const char *writeFmt, va_list args);
+ void VPrintfLine(Line line, const char *writeFmt, va_list args);
+ void Printf(Line line, INT32 startingColumn, const char *writeFmt, ...);
+ void PrintfLine(Line line, const char *writeFmt, ...);
+
+ void Clear();
+
+
+protected:
+ DriverStationLCD();
+
+private:
+ static void InitTask(DriverStationLCD *ds);
+ static DriverStationLCD *m_instance;
+ DISALLOW_COPY_AND_ASSIGN(DriverStationLCD);
+
+ char *m_textBuffer;
+ SEM_ID m_textBufferSemaphore;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Encoder.cpp b/aos/externals/WPILib/WPILib/Encoder.cpp
new file mode 100644
index 0000000..e67b56b
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Encoder.cpp
@@ -0,0 +1,513 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Encoder.h"
+#include "DigitalInput.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+static Resource *quadEncoders = NULL;
+
+/**
+ * Common initialization code for Encoders.
+ * This code allocates resources for Encoders and is common to all constructors.
+ * @param reverseDirection If true, counts down instead of up (this is all relative)
+ * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
+ * selected, then an encoder FPGA object is used and the returned counts will be 4x the encoder
+ * spec'd value since all rising and falling edges are counted. If 1X or 2X are selected then
+ * a counter object will be used and the returned value will either exactly match the spec'd count
+ * or be double (2x) the spec'd count.
+ */
+void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType)
+{
+ m_encodingType = encodingType;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ switch (encodingType)
+ {
+ case k4X:
+ Resource::CreateResourceObject(&quadEncoders, tEncoder::kNumSystems);
+ UINT32 index = quadEncoders->Allocate("4X Encoder");
+ if (index == ~0ul)
+ {
+ CloneError(quadEncoders);
+ return;
+ }
+ if (m_aSource->StatusIsFatal())
+ {
+ CloneError(m_aSource);
+ return;
+ }
+ if (m_bSource->StatusIsFatal())
+ {
+ CloneError(m_bSource);
+ return;
+ }
+ m_index = index;
+ m_encoder = tEncoder::create(m_index, &localStatus);
+ m_encoder->writeConfig_ASource_Module(m_aSource->GetModuleForRouting(), &localStatus);
+ m_encoder->writeConfig_ASource_Channel(m_aSource->GetChannelForRouting(), &localStatus);
+ m_encoder->writeConfig_ASource_AnalogTrigger(m_aSource->GetAnalogTriggerForRouting(), &localStatus);
+ m_encoder->writeConfig_BSource_Module(m_bSource->GetModuleForRouting(), &localStatus);
+ m_encoder->writeConfig_BSource_Channel(m_bSource->GetChannelForRouting(), &localStatus);
+ m_encoder->writeConfig_BSource_AnalogTrigger(m_bSource->GetAnalogTriggerForRouting(), &localStatus);
+ m_encoder->strobeReset(&localStatus);
+ m_encoder->writeConfig_Reverse(reverseDirection, &localStatus);
+ m_encoder->writeTimerConfig_AverageSize(4, &localStatus);
+ m_counter = NULL;
+ break;
+ case k1X:
+ case k2X:
+ m_counter = new Counter(m_encodingType, m_aSource, m_bSource, reverseDirection);
+ m_index = m_counter->GetIndex();
+ break;
+ }
+ m_distancePerPulse = 1.0;
+ m_pidSource = kDistance;
+ wpi_setError(localStatus);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Encoder, m_index, encodingType);
+}
+
+/**
+ * Encoder constructor.
+ * Construct a Encoder given a and b modules and channels fully specified.
+ * @param aModuleNumber The a channel digital input module.
+ * @param aChannel The a channel digital input channel.
+ * @param bModuleNumber The b channel digital input module.
+ * @param bChannel The b channel digital input channel.
+ * @param reverseDirection represents the orientation of the encoder and inverts the output values
+ * if necessary so forward represents positive values.
+ * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
+ * selected, then an encoder FPGA object is used and the returned counts will be 4x the encoder
+ * spec'd value since all rising and falling edges are counted. If 1X or 2X are selected then
+ * a counter object will be used and the returned value will either exactly match the spec'd count
+ * or be double (2x) the spec'd count.
+ */
+Encoder::Encoder(UINT8 aModuleNumber, UINT32 aChannel,
+ UINT8 bModuleNumber, UINT32 bChannel,
+ bool reverseDirection, EncodingType encodingType) :
+ m_encoder(NULL),
+ m_counter(NULL)
+{
+ m_aSource = new DigitalInput(aModuleNumber, aChannel);
+ m_bSource = new DigitalInput(bModuleNumber, bChannel);
+ InitEncoder(reverseDirection, encodingType);
+ m_allocatedASource = true;
+ m_allocatedBSource = true;
+}
+
+/**
+ * Encoder constructor.
+ * Construct a Encoder given a and b channels assuming the default module.
+ * @param aChannel The a channel digital input channel.
+ * @param bChannel The b channel digital input channel.
+ * @param reverseDirection represents the orientation of the encoder and inverts the output values
+ * if necessary so forward represents positive values.
+ * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
+ * selected, then an encoder FPGA object is used and the returned counts will be 4x the encoder
+ * spec'd value since all rising and falling edges are counted. If 1X or 2X are selected then
+ * a counter object will be used and the returned value will either exactly match the spec'd count
+ * or be double (2x) the spec'd count.
+ */
+Encoder::Encoder(UINT32 aChannel, UINT32 bChannel, bool reverseDirection, EncodingType encodingType) :
+ m_encoder(NULL),
+ m_counter(NULL)
+{
+ m_aSource = new DigitalInput(aChannel);
+ m_bSource = new DigitalInput(bChannel);
+ InitEncoder(reverseDirection, encodingType);
+ m_allocatedASource = true;
+ m_allocatedBSource = true;
+}
+
+/**
+ * Encoder constructor.
+ * Construct a Encoder given a and b channels as digital inputs. This is used in the case
+ * where the digital inputs are shared. The Encoder class will not allocate the digital inputs
+ * and assume that they already are counted.
+ * @param aSource The source that should be used for the a channel.
+ * @param bSource the source that should be used for the b channel.
+ * @param reverseDirection represents the orientation of the encoder and inverts the output values
+ * if necessary so forward represents positive values.
+ * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
+ * selected, then an encoder FPGA object is used and the returned counts will be 4x the encoder
+ * spec'd value since all rising and falling edges are counted. If 1X or 2X are selected then
+ * a counter object will be used and the returned value will either exactly match the spec'd count
+ * or be double (2x) the spec'd count.
+ */
+Encoder::Encoder(DigitalSource *aSource, DigitalSource *bSource, bool reverseDirection, EncodingType encodingType) :
+ m_encoder(NULL),
+ m_counter(NULL)
+{
+ m_aSource = aSource;
+ m_bSource = bSource;
+ m_allocatedASource = false;
+ m_allocatedBSource = false;
+ if (m_aSource == NULL || m_bSource == NULL)
+ wpi_setWPIError(NullParameter);
+ else
+ InitEncoder(reverseDirection, encodingType);
+}
+
+/**
+ * Encoder constructor.
+ * Construct a Encoder given a and b channels as digital inputs. This is used in the case
+ * where the digital inputs are shared. The Encoder class will not allocate the digital inputs
+ * and assume that they already are counted.
+ * @param aSource The source that should be used for the a channel.
+ * @param bSource the source that should be used for the b channel.
+ * @param reverseDirection represents the orientation of the encoder and inverts the output values
+ * if necessary so forward represents positive values.
+ * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
+ * selected, then an encoder FPGA object is used and the returned counts will be 4x the encoder
+ * spec'd value since all rising and falling edges are counted. If 1X or 2X are selected then
+ * a counter object will be used and the returned value will either exactly match the spec'd count
+ * or be double (2x) the spec'd count.
+ */
+Encoder::Encoder(DigitalSource &aSource, DigitalSource &bSource, bool reverseDirection, EncodingType encodingType) :
+ m_encoder(NULL),
+ m_counter(NULL)
+{
+ m_aSource = &aSource;
+ m_bSource = &bSource;
+ m_allocatedASource = false;
+ m_allocatedBSource = false;
+ InitEncoder(reverseDirection, encodingType);
+}
+
+/**
+ * Free the resources for an Encoder.
+ * Frees the FPGA resources associated with an Encoder.
+ */
+Encoder::~Encoder()
+{
+ if (m_allocatedASource) delete m_aSource;
+ if (m_allocatedBSource) delete m_bSource;
+ if (m_counter)
+ {
+ delete m_counter;
+ }
+ else
+ {
+ quadEncoders->Free(m_index);
+ delete m_encoder;
+ }
+}
+
+/**
+ * Start the Encoder.
+ * Starts counting pulses on the Encoder device.
+ */
+void Encoder::Start()
+{
+ if (StatusIsFatal()) return;
+ if (m_counter)
+ m_counter->Start();
+ else
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_encoder->writeConfig_Enable(1, &localStatus);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Stops counting pulses on the Encoder device. The value is not changed.
+ */
+void Encoder::Stop()
+{
+ if (StatusIsFatal()) return;
+ if (m_counter)
+ m_counter->Stop();
+ else
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_encoder->writeConfig_Enable(0, &localStatus);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Gets the raw value from the encoder.
+ * The raw value is the actual count unscaled by the 1x, 2x, or 4x scale
+ * factor.
+ * @return Current raw count from the encoder
+ */
+INT32 Encoder::GetRaw()
+{
+ if (StatusIsFatal()) return 0;
+ INT32 value;
+ if (m_counter)
+ value = m_counter->Get();
+ else
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ value = m_encoder->readOutput_Value(&localStatus);
+ wpi_setError(localStatus);
+ }
+ return value;
+}
+
+/**
+ * Gets the current count.
+ * Returns the current count on the Encoder.
+ * This method compensates for the decoding type.
+ *
+ * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale factor.
+ */
+INT32 Encoder::Get()
+{
+ if (StatusIsFatal()) return 0;
+ return (INT32) (GetRaw() * DecodingScaleFactor());
+}
+
+/**
+ * Reset the Encoder distance to zero.
+ * Resets the current count to zero on the encoder.
+ */
+void Encoder::Reset()
+{
+ if (StatusIsFatal()) return;
+ if (m_counter)
+ m_counter->Reset();
+ else
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_encoder->strobeReset(&localStatus);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Returns the period of the most recent pulse.
+ * Returns the period of the most recent Encoder pulse in seconds.
+ * This method compenstates for the decoding type.
+ *
+ * @deprecated Use GetRate() in favor of this method. This returns unscaled periods and GetRate() scales using value from SetDistancePerPulse().
+ *
+ * @return Period in seconds of the most recent pulse.
+ */
+double Encoder::GetPeriod()
+{
+ if (StatusIsFatal()) return 0.0;
+ double measuredPeriod;
+ if (m_counter)
+ {
+ measuredPeriod = m_counter->GetPeriod();
+ }
+ else
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ tEncoder::tTimerOutput output = m_encoder->readTimerOutput(&localStatus);
+ double value;
+ if (output.Stalled)
+ {
+ // Return infinity
+ double zero = 0.0;
+ value = 1.0 / zero;
+ }
+ else
+ {
+ // output.Period is a fixed point number that counts by 2 (24 bits, 25 integer bits)
+ value = (double)(output.Period << 1) / (double)output.Count;
+ }
+ wpi_setError(localStatus);
+ measuredPeriod = value * 1.0e-6;
+ }
+ return measuredPeriod / DecodingScaleFactor();
+}
+
+/**
+ * Sets the maximum period for stopped detection.
+ * Sets the value that represents the maximum period of the Encoder before it will assume
+ * that the attached device is stopped. This timeout allows users to determine if the wheels or
+ * other shaft has stopped rotating.
+ * This method compensates for the decoding type.
+ *
+ * @deprecated Use SetMinRate() in favor of this method. This takes unscaled periods and SetMinRate() scales using value from SetDistancePerPulse().
+ *
+ * @param maxPeriod The maximum time between rising and falling edges before the FPGA will
+ * report the device stopped. This is expressed in seconds.
+ */
+void Encoder::SetMaxPeriod(double maxPeriod)
+{
+ if (StatusIsFatal()) return;
+ if (m_counter)
+ {
+ m_counter->SetMaxPeriod(maxPeriod * DecodingScaleFactor());
+ }
+ else
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_encoder->writeTimerConfig_StallPeriod((UINT32)(maxPeriod * 1.0e6 * DecodingScaleFactor()), &localStatus);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Determine if the encoder is stopped.
+ * Using the MaxPeriod value, a boolean is returned that is true if the encoder is considered
+ * stopped and false if it is still moving. A stopped encoder is one where the most recent pulse
+ * width exceeds the MaxPeriod.
+ * @return True if the encoder is considered stopped.
+ */
+bool Encoder::GetStopped()
+{
+ if (StatusIsFatal()) return true;
+ if (m_counter)
+ {
+ return m_counter->GetStopped();
+ }
+ else
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool value = m_encoder->readTimerOutput_Stalled(&localStatus) != 0;
+ wpi_setError(localStatus);
+ return value;
+ }
+}
+
+/**
+ * The last direction the encoder value changed.
+ * @return The last direction the encoder value changed.
+ */
+bool Encoder::GetDirection()
+{
+ if (StatusIsFatal()) return false;
+ if (m_counter)
+ {
+ return m_counter->GetDirection();
+ }
+ else
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool value = m_encoder->readOutput_Direction(&localStatus);
+ wpi_setError(localStatus);
+ return value;
+ }
+}
+
+/**
+ * The scale needed to convert a raw counter value into a number of encoder pulses.
+ */
+double Encoder::DecodingScaleFactor()
+{
+ if (StatusIsFatal()) return 0.0;
+ switch (m_encodingType)
+ {
+ case k1X:
+ return 1.0;
+ case k2X:
+ return 0.5;
+ case k4X:
+ return 0.25;
+ default:
+ return 0.0;
+ }
+}
+
+/**
+ * Get the distance the robot has driven since the last reset.
+ *
+ * @return The distance driven since the last reset as scaled by the value from SetDistancePerPulse().
+ */
+double Encoder::GetDistance()
+{
+ if (StatusIsFatal()) return 0.0;
+ return GetRaw() * DecodingScaleFactor() * m_distancePerPulse;
+}
+
+/**
+ * Get the current rate of the encoder.
+ * Units are distance per second as scaled by the value from SetDistancePerPulse().
+ *
+ * @return The current rate of the encoder.
+ */
+double Encoder::GetRate()
+{
+ if (StatusIsFatal()) return 0.0;
+ return (m_distancePerPulse / GetPeriod());
+}
+
+/**
+ * Set the minimum rate of the device before the hardware reports it stopped.
+ *
+ * @param minRate The minimum rate. The units are in distance per second as scaled by the value from SetDistancePerPulse().
+ */
+void Encoder::SetMinRate(double minRate)
+{
+ if (StatusIsFatal()) return;
+ SetMaxPeriod(m_distancePerPulse / minRate);
+}
+
+/**
+ * Set the distance per pulse for this encoder.
+ * This sets the multiplier used to determine the distance driven based on the count value
+ * from the encoder.
+ * Do not include the decoding type in this scale. The library already compensates for the decoding type.
+ * Set this value based on the encoder's rated Pulses per Revolution and
+ * factor in gearing reductions following the encoder shaft.
+ * This distance can be in any units you like, linear or angular.
+ *
+ * @param distancePerPulse The scale factor that will be used to convert pulses to useful units.
+ */
+void Encoder::SetDistancePerPulse(double distancePerPulse)
+{
+ if (StatusIsFatal()) return;
+ m_distancePerPulse = distancePerPulse;
+}
+
+/**
+ * Set the direction sensing for this encoder.
+ * This sets the direction sensing on the encoder so that it could count in the correct
+ * software direction regardless of the mounting.
+ * @param reverseDirection true if the encoder direction should be reversed
+ */
+void Encoder::SetReverseDirection(bool reverseDirection)
+{
+ if (StatusIsFatal()) return;
+ if (m_counter)
+ {
+ m_counter->SetReverseDirection(reverseDirection);
+ }
+ else
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_encoder->writeConfig_Reverse(reverseDirection, &localStatus);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Set which parameter of the encoder you are using as a process control variable.
+ *
+ * @param pidSource An enum to select the parameter.
+ */
+void Encoder::SetPIDSourceParameter(PIDSourceParameter pidSource)
+{
+ if (StatusIsFatal()) return;
+ m_pidSource = pidSource;
+}
+
+/**
+ * Implement the PIDSource interface.
+ *
+ * @return The current value of the selected source parameter.
+ */
+double Encoder::PIDGet()
+{
+ if (StatusIsFatal()) return 0.0;
+ switch (m_pidSource)
+ {
+ case kDistance:
+ return GetDistance();
+ case kRate:
+ return GetRate();
+ default:
+ return 0.0;
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/Encoder.h b/aos/externals/WPILib/WPILib/Encoder.h
new file mode 100644
index 0000000..f08e706
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Encoder.h
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef QUAD_ENCODER_H_
+#define QUAD_ENCODER_H_
+
+#include "ChipObject.h"
+#include "CounterBase.h"
+#include "SensorBase.h"
+#include "Counter.h"
+#include "PIDSource.h"
+
+class DigitalSource;
+
+/**
+ * Class to read quad encoders.
+ * Quadrature encoders are devices that count shaft rotation and can sense direction. The output of
+ * the QuadEncoder class is an integer that can count either up or down, and can go negative for
+ * reverse direction counting. When creating QuadEncoders, a direction is supplied that changes the
+ * sense of the output to make code more readable if the encoder is mounted such that forward movement
+ * generates negative values. Quadrature encoders have two digital outputs, an A Channel and a B Channel
+ * that are out of phase with each other to allow the FPGA to do direction sensing.
+ */
+class Encoder: public SensorBase, public CounterBase, public PIDSource
+{
+public:
+ typedef enum {kDistance, kRate} PIDSourceParameter;
+
+ Encoder(UINT32 aChannel, UINT32 bChannel, bool reverseDirection=false, EncodingType encodingType = k4X);
+ Encoder(UINT8 aModuleNumber, UINT32 aChannel, UINT8 bModuleNumber, UINT32 _bChannel, bool reverseDirection=false, EncodingType encodingType = k4X);
+ Encoder(DigitalSource *aSource, DigitalSource *bSource, bool reverseDirection=false, EncodingType encodingType = k4X);
+ Encoder(DigitalSource &aSource, DigitalSource &bSource, bool reverseDirection=false, EncodingType encodingType = k4X);
+ virtual ~Encoder();
+
+ // CounterBase interface
+ void Start();
+ INT32 Get();
+ INT32 GetRaw();
+ void Reset();
+ void Stop();
+ double GetPeriod();
+ void SetMaxPeriod(double maxPeriod);
+ bool GetStopped();
+ bool GetDirection();
+ double GetDistance();
+ double GetRate();
+ void SetMinRate(double minRate);
+ void SetDistancePerPulse(double distancePerPulse);
+ void SetReverseDirection(bool reverseDirection);
+
+ void SetPIDSourceParameter(PIDSourceParameter pidSource);
+ double PIDGet();
+
+private:
+ void InitEncoder(bool _reverseDirection, EncodingType encodingType);
+ double DecodingScaleFactor();
+
+ DigitalSource *m_aSource; // the A phase of the quad encoder
+ DigitalSource *m_bSource; // the B phase of the quad encoder
+ bool m_allocatedASource; // was the A source allocated locally?
+ bool m_allocatedBSource; // was the B source allocated locally?
+ tEncoder* m_encoder;
+ UINT8 m_index;
+ double m_distancePerPulse; // distance of travel for each encoder tick
+ Counter *m_counter; // Counter object for 1x and 2x encoding
+ EncodingType m_encodingType; // Encoding type
+ PIDSourceParameter m_pidSource;// Encoder parameter that sources a PID controller
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Error.cpp b/aos/externals/WPILib/WPILib/Error.cpp
new file mode 100644
index 0000000..30f0cbc
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Error.cpp
@@ -0,0 +1,122 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Error.h"
+
+#include <taskLib.h>
+
+#include "NetworkCommunication/FRCComm.h"
+#include "Timer.h"
+#include "Utility.h"
+
+bool Error::m_stackTraceEnabled = false;
+bool Error::m_suspendOnErrorEnabled = false;
+
+Error::Error()
+ : m_code(0)
+ , m_lineNumber(0)
+ , m_originatingObject(NULL)
+ , m_timestamp (0.0)
+{}
+
+Error::~Error()
+{}
+
+void Error::Clone(Error &error)
+{
+ m_code = error.m_code;
+ m_message = error.m_message;
+ m_filename = error.m_filename;
+ m_function = error.m_function;
+ m_lineNumber = error.m_lineNumber;
+ m_originatingObject = error.m_originatingObject;
+ m_timestamp = error.m_timestamp;
+}
+
+Error::Code Error::GetCode() const
+{ return m_code; }
+
+const char * Error::GetMessage() const
+{ return m_message.c_str(); }
+
+const char * Error::GetFilename() const
+{ return m_filename.c_str(); }
+
+const char * Error::GetFunction() const
+{ return m_function.c_str(); }
+
+UINT32 Error::GetLineNumber() const
+{ return m_lineNumber; }
+
+const ErrorBase* Error::GetOriginatingObject() const
+{ return m_originatingObject; }
+
+double Error::GetTime() const
+{ return m_timestamp; }
+
+void Error::Set(Code code, const char* contextMessage, const char* filename, const char* function, UINT32 lineNumber, const ErrorBase* originatingObject)
+{
+ m_code = code;
+ m_message = contextMessage;
+ m_filename = filename;
+ m_function = function;
+ m_lineNumber = lineNumber;
+ m_originatingObject = originatingObject;
+ m_timestamp = GetTime();
+
+ Report();
+
+ if (m_suspendOnErrorEnabled) taskSuspend(0);
+}
+
+void Error::Report()
+{
+ // Error string buffers
+ char *error = new char[256];
+ char *error_with_code = new char[256];
+
+ // Build error strings
+ if (m_code != -1)
+ {
+ snprintf(error, 256, "%s: status = %d (0x%08X) %s ...in %s() in %s at line %d\n",
+ m_code < 0 ? "ERROR" : "WARNING", (INT32)m_code, (UINT32)m_code, m_message.c_str(),
+ m_function.c_str(), m_filename.c_str(), m_lineNumber);
+ sprintf(error_with_code,"<Code>%d %s", (INT32)m_code, error);
+ } else {
+ snprintf(error, 256, "ERROR: %s ...in %s() in %s at line %d\n", m_message.c_str(),
+ m_function.c_str(), m_filename.c_str(), m_lineNumber);
+ strcpy(error_with_code, error);
+ }
+ // TODO: Add logging to disk
+
+ // Send to the DriverStation
+ setErrorData(error_with_code, strlen(error_with_code), 100);
+
+ delete [] error_with_code;
+
+ // Print to console
+ printf("\n\n>>>>%s", error);
+
+ delete [] error;
+
+ if (m_stackTraceEnabled)
+ {
+ printf("-----------<Stack Trace>----------------\n");
+ wpi_selfTrace();
+ }
+}
+
+void Error::Clear()
+{
+ m_code = 0;
+ m_message = "";
+ m_filename = "";
+ m_function = "";
+ m_lineNumber = 0;
+ m_originatingObject = NULL;
+ m_timestamp = 0.0;
+}
+
diff --git a/aos/externals/WPILib/WPILib/Error.h b/aos/externals/WPILib/WPILib/Error.h
new file mode 100644
index 0000000..a80fe06
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Error.h
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef _ERROR_H
+#define _ERROR_H
+
+#include "Base.h"
+#include "ChipObject/NiRio.h"
+#include <string>
+#include <vxWorks.h>
+
+// Forward declarations
+class ErrorBase;
+
+/**
+ * Error object represents a library error.
+ */
+class Error
+{
+public:
+ typedef tRioStatusCode Code;
+
+ Error();
+ ~Error();
+ void Clone(Error &error);
+ Code GetCode() const;
+ const char *GetMessage() const;
+ const char *GetFilename() const;
+ const char *GetFunction() const;
+ UINT32 GetLineNumber() const;
+ const ErrorBase* GetOriginatingObject() const;
+ double GetTime() const;
+ void Clear();
+ void Set(Code code, const char* contextMessage, const char* filename,
+ const char *function, UINT32 lineNumber, const ErrorBase* originatingObject);
+ static void EnableStackTrace(bool enable) { m_stackTraceEnabled=enable; }
+ static void EnableSuspendOnError(bool enable) { m_suspendOnErrorEnabled=enable; }
+
+private:
+ void Report();
+
+ Code m_code;
+ std::string m_message;
+ std::string m_filename;
+ std::string m_function;
+ UINT32 m_lineNumber;
+ const ErrorBase* m_originatingObject;
+ double m_timestamp;
+
+ static bool m_stackTraceEnabled;
+ static bool m_suspendOnErrorEnabled;
+ DISALLOW_COPY_AND_ASSIGN(Error);
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/ErrorBase.cpp b/aos/externals/WPILib/WPILib/ErrorBase.cpp
new file mode 100644
index 0000000..2722963
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ErrorBase.cpp
@@ -0,0 +1,215 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "ErrorBase.h"
+#include "Synchronized.h"
+#include "nivision.h"
+#define WPI_ERRORS_DEFINE_STRINGS
+#include "WPIErrors.h"
+
+#include <errnoLib.h>
+#include <symLib.h>
+#include <sysSymTbl.h>
+
+SEM_ID ErrorBase::_globalErrorMutex = semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+Error ErrorBase::_globalError;
+/**
+ * @brief Initialize the instance status to 0 for now.
+ */
+ErrorBase::ErrorBase()
+{}
+
+ErrorBase::~ErrorBase()
+{}
+
+/**
+ * @brief Retrieve the current error.
+ * Get the current error information associated with this sensor.
+ */
+Error& ErrorBase::GetError()
+{
+ return m_error;
+}
+
+const Error& ErrorBase::GetError() const
+{
+ return m_error;
+}
+
+/**
+ * @brief Clear the current error information associated with this sensor.
+ */
+void ErrorBase::ClearError() const
+{
+ m_error.Clear();
+}
+
+/**
+ * @brief Set error information associated with a C library call that set an error to the "errno" global variable.
+ *
+ * @param contextMessage A custom message from the code that set the error.
+ * @param filename Filename of the error source
+ * @param function Function of the error source
+ * @param lineNumber Line number of the error source
+ */
+void ErrorBase::SetErrnoError(const char *contextMessage,
+ const char* filename, const char* function, UINT32 lineNumber) const
+{
+ char err[256];
+ int errNo = errnoGet();
+ if (errNo == 0)
+ {
+ sprintf(err, "OK: %s", contextMessage);
+ }
+ else
+ {
+ char *statName = new char[MAX_SYS_SYM_LEN + 1];
+ int pval;
+ SYM_TYPE ptype;
+ symFindByValue(statSymTbl, errNo, statName, &pval, &ptype);
+ if (pval != errNo)
+ snprintf(err, 256, "Unknown errno 0x%08X: %s", errNo, contextMessage);
+ else
+ snprintf(err, 256, "%s (0x%08X): %s", statName, errNo, contextMessage);
+ delete [] statName;
+ }
+
+ // Set the current error information for this object.
+ m_error.Set(-1, err, filename, function, lineNumber, this);
+
+ // Update the global error if there is not one already set.
+ Synchronized mutex(_globalErrorMutex);
+ if (_globalError.GetCode() == 0) {
+ _globalError.Clone(m_error);
+ }
+}
+
+/**
+ * @brief Set the current error information associated from the nivision Imaq API.
+ *
+ * @param success The return from the function
+ * @param contextMessage A custom message from the code that set the error.
+ * @param filename Filename of the error source
+ * @param function Function of the error source
+ * @param lineNumber Line number of the error source
+ */
+void ErrorBase::SetImaqError(int success, const char *contextMessage, const char* filename, const char* function, UINT32 lineNumber) const
+{
+ // If there was an error
+ if (success <= 0) {
+ char err[256];
+ sprintf(err, "%s: %s", contextMessage, imaqGetErrorText(imaqGetLastError()));
+
+ // Set the current error information for this object.
+ m_error.Set(imaqGetLastError(), err, filename, function, lineNumber, this);
+
+ // Update the global error if there is not one already set.
+ Synchronized mutex(_globalErrorMutex);
+ if (_globalError.GetCode() == 0) {
+ _globalError.Clone(m_error);
+ }
+ }
+}
+
+/**
+ * @brief Set the current error information associated with this sensor.
+ *
+ * @param code The error code
+ * @param contextMessage A custom message from the code that set the error.
+ * @param filename Filename of the error source
+ * @param function Function of the error source
+ * @param lineNumber Line number of the error source
+ */
+void ErrorBase::SetError(Error::Code code, const char *contextMessage,
+ const char* filename, const char* function, UINT32 lineNumber) const
+{
+ // If there was an error
+ if (code != 0) {
+ // Set the current error information for this object.
+ m_error.Set(code, contextMessage, filename, function, lineNumber, this);
+
+ // Update the global error if there is not one already set.
+ Synchronized mutex(_globalErrorMutex);
+ if (_globalError.GetCode() == 0) {
+ _globalError.Clone(m_error);
+ }
+ }
+}
+
+/**
+ * @brief Set the current error information associated with this sensor.
+ *
+ * @param errorMessage The error message from WPIErrors.h
+ * @param contextMessage A custom message from the code that set the error.
+ * @param filename Filename of the error source
+ * @param function Function of the error source
+ * @param lineNumber Line number of the error source
+ */
+void ErrorBase::SetWPIError(const char *errorMessage, const char *contextMessage,
+ const char* filename, const char* function, UINT32 lineNumber) const
+{
+ char err[256];
+ sprintf(err, "%s: %s", errorMessage, contextMessage);
+
+ // Set the current error information for this object.
+ m_error.Set(-1, err, filename, function, lineNumber, this);
+
+ // Update the global error if there is not one already set.
+ Synchronized mutex(_globalErrorMutex);
+ if (_globalError.GetCode() == 0) {
+ _globalError.Clone(m_error);
+ }
+}
+
+void ErrorBase::CloneError(ErrorBase *rhs) const
+{
+ m_error.Clone(rhs->GetError());
+}
+
+/**
+@brief Check if the current error code represents a fatal error.
+
+@return true if the current error is fatal.
+*/
+bool ErrorBase::StatusIsFatal() const
+{
+ return m_error.GetCode() < 0;
+}
+
+void ErrorBase::SetGlobalError(Error::Code code, const char *contextMessage,
+ const char* filename, const char* function, UINT32 lineNumber)
+{
+ // If there was an error
+ if (code != 0) {
+ Synchronized mutex(_globalErrorMutex);
+
+ // Set the current error information for this object.
+ _globalError.Set(code, contextMessage, filename, function, lineNumber, NULL);
+ }
+}
+
+void ErrorBase::SetGlobalWPIError(const char *errorMessage, const char *contextMessage,
+ const char* filename, const char* function, UINT32 lineNumber)
+{
+ char err[256];
+ sprintf(err, "%s: %s", errorMessage, contextMessage);
+
+ Synchronized mutex(_globalErrorMutex);
+ if (_globalError.GetCode() != 0) {
+ _globalError.Clear();
+ }
+ _globalError.Set(-1, err, filename, function, lineNumber, NULL);
+}
+
+/**
+ * Retrieve the current global error.
+*/
+Error& ErrorBase::GetGlobalError()
+{
+ Synchronized mutex(_globalErrorMutex);
+ return _globalError;
+}
+
diff --git a/aos/externals/WPILib/WPILib/ErrorBase.h b/aos/externals/WPILib/WPILib/ErrorBase.h
new file mode 100644
index 0000000..f967562
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/ErrorBase.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef _ERROR_BASE_H
+#define _ERROR_BASE_H
+
+#include "Base.h"
+#include "ChipObject/NiRio.h"
+#include "Error.h"
+#include <semLib.h>
+#include <vxWorks.h>
+
+#define wpi_setErrnoErrorWithContext(context) (this->SetErrnoError((context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setErrnoError() (wpi_setErrnoErrorWithContext(""))
+#define wpi_setImaqErrorWithContext(code, context) (this->SetImaqError((code), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setErrorWithContext(code, context) (this->SetError((code), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setError(code) (wpi_setErrorWithContext(code, ""))
+#define wpi_setStaticErrorWithContext(object, code, context) (object->SetError((code), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setStaticError(object, code) (wpi_setStaticErrorWithContext(object, code, ""))
+#define wpi_setGlobalErrorWithContext(code, context) (ErrorBase::SetGlobalError((code), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setGlobalError(code) (wpi_setGlobalErrorWithContext(code, ""))
+#define wpi_setWPIErrorWithContext(error, context) (this->SetWPIError((wpi_error_s_##error), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setWPIError(error) (wpi_setWPIErrorWithContext(error, ""))
+#define wpi_setStaticWPIErrorWithContext(object, error, context) (object->SetWPIError((wpi_error_s_##error), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setStaticWPIError(object, error) (wpi_setStaticWPIErrorWithContext(object, error, ""))
+#define wpi_setGlobalWPIErrorWithContext(error, context) (ErrorBase::SetGlobalWPIError((wpi_error_s_##error), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setGlobalWPIError(error) (wpi_setGlobalWPIErrorWithContext(error, ""))
+
+/**
+ * Base class for most objects.
+ * ErrorBase is the base class for most objects since it holds the generated error
+ * for that object. In addition, there is a single instance of a global error object
+ */
+class ErrorBase
+{
+//TODO: Consider initializing instance variables and cleanup in destructor
+public:
+ virtual ~ErrorBase();
+ virtual Error& GetError();
+ virtual const Error& GetError() const;
+ virtual void SetErrnoError(const char *contextMessage,
+ const char* filename, const char* function, UINT32 lineNumber) const;
+ virtual void SetImaqError(int success, const char *contextMessage,
+ const char* filename, const char* function, UINT32 lineNumber) const;
+ virtual void SetError(Error::Code code, const char *contextMessage,
+ const char* filename, const char* function, UINT32 lineNumber) const;
+ virtual void SetWPIError(const char *errorMessage, const char *contextMessage,
+ const char* filename, const char* function, UINT32 lineNumber) const;
+ virtual void CloneError(ErrorBase *rhs) const;
+ virtual void ClearError() const;
+ virtual bool StatusIsFatal() const;
+ static void SetGlobalError(Error::Code code, const char *contextMessage,
+ const char* filename, const char* function, UINT32 lineNumber);
+ static void SetGlobalWPIError(const char *errorMessage, const char *contextMessage,
+ const char* filename, const char* function, UINT32 lineNumber);
+ static Error& GetGlobalError();
+protected:
+ mutable Error m_error;
+ // TODO: Replace globalError with a global list of all errors.
+ static SEM_ID _globalErrorMutex;
+ static Error _globalError;
+ ErrorBase();
+private:
+ DISALLOW_COPY_AND_ASSIGN(ErrorBase);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/GearTooth.cpp b/aos/externals/WPILib/WPILib/GearTooth.cpp
new file mode 100644
index 0000000..d0f8780
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/GearTooth.cpp
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "GearTooth.h"
+
+const double GearTooth::kGearToothThreshold;
+
+/**
+ * Common code called by the constructors.
+ */
+void GearTooth::EnableDirectionSensing(bool directionSensitive)
+{
+ if (directionSensitive)
+ {
+ SetPulseLengthMode(kGearToothThreshold);
+ }
+}
+
+/**
+ * Construct a GearTooth sensor given a channel.
+ *
+ * The default module is assumed.
+ *
+ * @param channel The GPIO channel on the digital module that the sensor is connected to.
+ * @param directionSensitive Enable the pulse length decoding in hardware to specify count direction.
+ */
+GearTooth::GearTooth(UINT32 channel, bool directionSensitive)
+ : Counter(channel)
+{
+ EnableDirectionSensing(directionSensitive);
+}
+
+/**
+ * Construct a GearTooth sensor given a channel and module.
+ *
+ * @param moduleNumber The digital module (1 or 2).
+ * @param channel The GPIO channel on the digital module that the sensor is connected to.
+ * @param directionSensitive Enable the pulse length decoding in hardware to specify count direction.
+ */
+GearTooth::GearTooth(UINT8 moduleNumber, UINT32 channel, bool directionSensitive)
+ : Counter(moduleNumber, channel)
+{
+ EnableDirectionSensing(directionSensitive);
+}
+
+/**
+ * Construct a GearTooth sensor given a digital input.
+ * This should be used when sharing digial inputs.
+ *
+ * @param source An object that fully descibes the input that the sensor is connected to.
+ * @param directionSensitive Enable the pulse length decoding in hardware to specify count direction.
+ */
+GearTooth::GearTooth(DigitalSource *source, bool directionSensitive)
+ : Counter(source)
+{
+ EnableDirectionSensing(directionSensitive);
+}
+
+GearTooth::GearTooth(DigitalSource &source, bool directionSensitive): Counter(source)
+{
+ EnableDirectionSensing(directionSensitive);
+}
+
+/**
+ * Free the resources associated with a gear tooth sensor.
+ */
+GearTooth::~GearTooth()
+{
+}
+
diff --git a/aos/externals/WPILib/WPILib/GearTooth.h b/aos/externals/WPILib/WPILib/GearTooth.h
new file mode 100644
index 0000000..fa65555
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/GearTooth.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef GEAR_TOOTH_H_
+#define GEAR_TOOTH_H_
+
+#include "Counter.h"
+
+/**
+ * Alias for counter class.
+ * Implement the gear tooth sensor supplied by FIRST. Currently there is no reverse sensing on
+ * the gear tooth sensor, but in future versions we might implement the necessary timing in the
+ * FPGA to sense direction.
+ */
+class GearTooth : public Counter
+{
+public:
+ /// 55 uSec for threshold
+ static const double kGearToothThreshold = 55e-6;
+ GearTooth(UINT32 channel, bool directionSensitive = false);
+ GearTooth(UINT8 moduleNumber, UINT32 channel, bool directionSensitive = false);
+ GearTooth(DigitalSource *source, bool directionSensitive = false);
+ GearTooth(DigitalSource &source, bool directionSensitive = false);
+ virtual ~GearTooth();
+ void EnableDirectionSensing(bool directionSensitive);
+};
+
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/GenericHID.h b/aos/externals/WPILib/WPILib/GenericHID.h
new file mode 100644
index 0000000..6442d6d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/GenericHID.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef GENERIC_HID_H
+#define GENERIC_HID_H
+
+#include <vxWorks.h>
+
+/** GenericHID Interface
+ */
+class GenericHID
+{
+public:
+ typedef enum {
+ kLeftHand = 0,
+ kRightHand = 1
+ } JoystickHand;
+
+ virtual ~GenericHID() {}
+
+ virtual float GetX(JoystickHand hand = kRightHand) = 0;
+ virtual float GetY(JoystickHand hand = kRightHand) = 0;
+ virtual float GetZ() = 0;
+ virtual float GetTwist() = 0;
+ virtual float GetThrottle() = 0;
+ virtual float GetRawAxis(UINT32 axis) = 0;
+
+ virtual bool GetTrigger(JoystickHand hand = kRightHand) = 0;
+ virtual bool GetTop(JoystickHand hand = kRightHand) = 0;
+ virtual bool GetBumper(JoystickHand hand = kRightHand) = 0;
+ virtual bool GetRawButton(UINT32 button) = 0;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Gyro.cpp b/aos/externals/WPILib/WPILib/Gyro.cpp
new file mode 100644
index 0000000..179c0ad
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Gyro.cpp
@@ -0,0 +1,187 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Gyro.h"
+#include "AnalogChannel.h"
+#include "AnalogModule.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+
+const UINT32 Gyro::kOversampleBits;
+const UINT32 Gyro::kAverageBits;
+const float Gyro::kSamplesPerSecond;
+const float Gyro::kCalibrationSampleTime;
+const float Gyro::kDefaultVoltsPerDegreePerSecond;
+
+/**
+ * Initialize the gyro.
+ * Calibrate the gyro by running for a number of samples and computing the center value for this
+ * part. Then use the center value as the Accumulator center value for subsequent measurements.
+ * It's important to make sure that the robot is not moving while the centering calculations are
+ * in progress, this is typically done when the robot is first turned on while it's sitting at
+ * rest before the competition starts.
+ */
+void Gyro::InitGyro()
+{
+ if (!m_analog->IsAccumulatorChannel())
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange,
+ "moduleNumber and/or channel (must be accumulator channel)");
+ if (m_channelAllocated)
+ {
+ delete m_analog;
+ m_analog = NULL;
+ }
+ return;
+ }
+
+ m_voltsPerDegreePerSecond = kDefaultVoltsPerDegreePerSecond;
+ m_analog->SetAverageBits(kAverageBits);
+ m_analog->SetOversampleBits(kOversampleBits);
+ float sampleRate = kSamplesPerSecond *
+ (1 << (kAverageBits + kOversampleBits));
+ m_analog->GetModule()->SetSampleRate(sampleRate);
+ Wait(1.0);
+
+ m_analog->InitAccumulator();
+ Wait(kCalibrationSampleTime);
+
+ INT64 value;
+ UINT32 count;
+ m_analog->GetAccumulatorOutput(&value, &count);
+
+ UINT32 center = (UINT32)((float)value / (float)count + .5);
+
+ m_offset = ((float)value / (float)count) - (float)center;
+
+ m_analog->SetAccumulatorCenter(center);
+ m_analog->SetAccumulatorDeadband(0); ///< TODO: compute / parameterize this
+ m_analog->ResetAccumulator();
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Gyro, m_analog->GetChannel(), m_analog->GetModuleNumber() - 1);
+}
+
+/**
+ * Gyro constructor given a slot and a channel.
+ *
+ * @param moduleNumber The analog module the gyro is connected to (1).
+ * @param channel The analog channel the gyro is connected to (1 or 2).
+ */
+Gyro::Gyro(UINT8 moduleNumber, UINT32 channel)
+{
+ m_analog = new AnalogChannel(moduleNumber, channel);
+ m_channelAllocated = true;
+ InitGyro();
+}
+
+/**
+ * Gyro constructor with only a channel.
+ *
+ * Use the default analog module slot.
+ *
+ * @param channel The analog channel the gyro is connected to.
+ */
+Gyro::Gyro(UINT32 channel)
+{
+ m_analog = new AnalogChannel(channel);
+ m_channelAllocated = true;
+ InitGyro();
+}
+
+/**
+ * Gyro constructor with a precreated analog channel object.
+ * Use this constructor when the analog channel needs to be shared. There
+ * is no reference counting when an AnalogChannel is passed to the gyro.
+ * @param channel The AnalogChannel object that the gyro is connected to.
+ */
+Gyro::Gyro(AnalogChannel *channel)
+{
+ m_analog = channel;
+ m_channelAllocated = false;
+ if (channel == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ }
+ else
+ {
+ InitGyro();
+ }
+}
+
+Gyro::Gyro(AnalogChannel &channel)
+{
+ m_analog = &channel;
+ m_channelAllocated = false;
+ InitGyro();
+}
+
+/**
+ * Reset the gyro.
+ * Resets the gyro to a heading of zero. This can be used if there is significant
+ * drift in the gyro and it needs to be recalibrated after it has been running.
+ */
+void Gyro::Reset()
+{
+ m_analog->ResetAccumulator();
+}
+
+/**
+ * Delete (free) the accumulator and the analog components used for the gyro.
+ */
+Gyro::~Gyro()
+{
+ if (m_channelAllocated)
+ delete m_analog;
+}
+
+/**
+ * Return the actual angle in degrees that the robot is currently facing.
+ *
+ * The angle is based on the current accumulator value corrected by the oversampling rate, the
+ * gyro type and the A/D calibration values.
+ * The angle is continuous, that is can go beyond 360 degrees. This make algorithms that wouldn't
+ * want to see a discontinuity in the gyro output as it sweeps past 0 on the second time around.
+ *
+ * @return the current heading of the robot in degrees. This heading is based on integration
+ * of the returned rate from the gyro.
+ */
+float Gyro::GetAngle( void )
+{
+ INT64 rawValue;
+ UINT32 count;
+ m_analog->GetAccumulatorOutput(&rawValue, &count);
+
+ INT64 value = rawValue - (INT64)((float)count * m_offset);
+
+ double scaledValue = value * 1e-9 * (double)m_analog->GetLSBWeight() * (double)(1 << m_analog->GetAverageBits()) /
+ (m_analog->GetModule()->GetSampleRate() * m_voltsPerDegreePerSecond);
+
+ return (float)scaledValue;
+}
+
+
+/**
+ * Set the gyro type based on the sensitivity.
+ * This takes the number of volts/degree/second sensitivity of the gyro and uses it in subsequent
+ * calculations to allow the code to work with multiple gyros.
+ *
+ * @param voltsPerDegreePerSecond The type of gyro specified as the voltage that represents one degree/second.
+ */
+void Gyro::SetSensitivity( float voltsPerDegreePerSecond )
+{
+ m_voltsPerDegreePerSecond = voltsPerDegreePerSecond;
+}
+
+/**
+ * Get the angle in degrees for the PIDSource base object.
+ *
+ * @return The angle in degrees.
+ */
+double Gyro::PIDGet()
+{
+ return GetAngle();
+}
diff --git a/aos/externals/WPILib/WPILib/Gyro.h b/aos/externals/WPILib/WPILib/Gyro.h
new file mode 100644
index 0000000..dc3a4bc
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Gyro.h
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef GYRO_H_
+#define GYRO_H_
+
+#include "SensorBase.h"
+#include "PIDSource.h"
+
+class AnalogChannel;
+class AnalogModule;
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position.
+ * The Gyro class tracks the robots heading based on the starting position. As the robot
+ * rotates the new heading is computed by integrating the rate of rotation returned
+ * by the sensor. When the class is instantiated, it does a short calibration routine
+ * where it samples the gyro while at rest to determine the default offset. This is
+ * subtracted from each sample to determine the heading. This gyro class must be used
+ * with a channel that is assigned one of the Analog accumulators from the FPGA. See
+ * AnalogChannel for the current accumulator assignments.
+ */
+class Gyro : public SensorBase, public PIDSource
+{
+public:
+ static const UINT32 kOversampleBits = 10;
+ static const UINT32 kAverageBits = 0;
+ static const float kSamplesPerSecond = 50.0;
+ static const float kCalibrationSampleTime = 5.0;
+ static const float kDefaultVoltsPerDegreePerSecond = 0.007;
+
+ Gyro(UINT8 moduleNumber, UINT32 channel);
+ explicit Gyro(UINT32 channel);
+ explicit Gyro(AnalogChannel *channel);
+ explicit Gyro(AnalogChannel &channel);
+ virtual ~Gyro();
+ virtual float GetAngle();
+ void SetSensitivity(float voltsPerDegreePerSecond);
+ virtual void Reset();
+
+ // PIDSource interface
+ double PIDGet();
+
+private:
+ void InitGyro();
+
+ AnalogChannel *m_analog;
+ float m_voltsPerDegreePerSecond;
+ float m_offset;
+ bool m_channelAllocated;
+};
+#endif
diff --git a/aos/externals/WPILib/WPILib/HiTechnicCompass.cpp b/aos/externals/WPILib/WPILib/HiTechnicCompass.cpp
new file mode 100644
index 0000000..f925b33
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/HiTechnicCompass.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "HiTechnicCompass.h"
+#include "DigitalModule.h"
+#include "I2C.h"
+#include "WPIErrors.h"
+
+const UINT8 HiTechnicCompass::kAddress;
+const UINT8 HiTechnicCompass::kManufacturerBaseRegister;
+const UINT8 HiTechnicCompass::kManufacturerSize;
+const UINT8 HiTechnicCompass::kSensorTypeBaseRegister;
+const UINT8 HiTechnicCompass::kSensorTypeSize;
+const UINT8 HiTechnicCompass::kHeadingRegister;
+
+/**
+ * Constructor.
+ *
+ * @param moduleNumber The digital module that the sensor is plugged into (1 or 2).
+ */
+HiTechnicCompass::HiTechnicCompass(UINT8 moduleNumber)
+ : m_i2c (NULL)
+{
+ DigitalModule *module = DigitalModule::GetInstance(moduleNumber);
+ if (module)
+ {
+ m_i2c = module->GetI2C(kAddress);
+
+ // Verify Sensor
+ const UINT8 kExpectedManufacturer[] = "HiTechnc";
+ const UINT8 kExpectedSensorType[] = "Compass ";
+ if ( ! m_i2c->VerifySensor(kManufacturerBaseRegister, kManufacturerSize, kExpectedManufacturer) )
+ {
+ wpi_setWPIError(CompassManufacturerError);
+ return;
+ }
+ if ( ! m_i2c->VerifySensor(kSensorTypeBaseRegister, kSensorTypeSize, kExpectedSensorType) )
+ {
+ wpi_setWPIError(CompassTypeError);
+ }
+ }
+}
+
+/**
+ * Destructor.
+ */
+HiTechnicCompass::~HiTechnicCompass()
+{
+ delete m_i2c;
+ m_i2c = NULL;
+}
+
+/**
+ * Get the compass angle in degrees.
+ *
+ * The resolution of this reading is 1 degree.
+ *
+ * @return Angle of the compass in degrees.
+ */
+float HiTechnicCompass::GetAngle()
+{
+ UINT16 heading = 0;
+ if (m_i2c)
+ {
+ m_i2c->Read(kHeadingRegister, sizeof(heading), (UINT8 *)&heading);
+
+ // Sensor is little endian... swap bytes
+ heading = (heading >> 8) | (heading << 8);
+ }
+ return (float)heading;
+}
+
diff --git a/aos/externals/WPILib/WPILib/HiTechnicCompass.h b/aos/externals/WPILib/WPILib/HiTechnicCompass.h
new file mode 100644
index 0000000..fb94b1a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/HiTechnicCompass.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __HiTechnicCompass_h__
+#define __HiTechnicCompass_h__
+
+#include "SensorBase.h"
+
+class I2C;
+
+/**
+ * HiTechnic NXT Compass.
+ *
+ * This class alows access to a HiTechnic NXT Compass on an I2C bus.
+ * These sensors to not allow changing addresses so you cannot have more
+ * than one on a single bus.
+ *
+ * Details on the sensor can be found here:
+ * http://www.hitechnic.com/index.html?lang=en-us&target=d17.html
+ *
+ * @todo Implement a calibration method for the sensor.
+ */
+class HiTechnicCompass : public SensorBase
+{
+public:
+ explicit HiTechnicCompass(UINT8 moduleNumber);
+ virtual ~HiTechnicCompass();
+ float GetAngle();
+
+private:
+ static const UINT8 kAddress = 0x02;
+ static const UINT8 kManufacturerBaseRegister = 0x08;
+ static const UINT8 kManufacturerSize = 0x08;
+ static const UINT8 kSensorTypeBaseRegister = 0x10;
+ static const UINT8 kSensorTypeSize = 0x08;
+ static const UINT8 kHeadingRegister = 0x44;
+
+ I2C* m_i2c;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/I2C.cpp b/aos/externals/WPILib/WPILib/I2C.cpp
new file mode 100644
index 0000000..c3c5277
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/I2C.cpp
@@ -0,0 +1,234 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "I2C.h"
+#include "DigitalModule.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Synchronized.h"
+#include "WPIErrors.h"
+#include <taskLib.h>
+
+SEM_ID I2C::m_semaphore = NULL;
+UINT32 I2C::m_objCount = 0;
+
+/**
+ * Constructor.
+ *
+ * @param module The Digital Module to which the device is conneted.
+ * @param deviceAddress The address of the device on the I2C bus.
+ */
+I2C::I2C(DigitalModule *module, UINT8 deviceAddress)
+ : m_module (module)
+ , m_deviceAddress (deviceAddress)
+ , m_compatibilityMode (false)
+{
+ if (m_semaphore == NULL)
+ {
+ m_semaphore = semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+ }
+ m_objCount++;
+
+ const char *cm = NULL;
+ if (m_compatibilityMode) cm = "C";
+ nUsageReporting::report(nUsageReporting::kResourceType_I2C, deviceAddress, module->GetNumber() - 1, cm);
+}
+
+/**
+ * Destructor.
+ */
+I2C::~I2C()
+{
+ m_objCount--;
+ if (m_objCount <= 0)
+ {
+ semDelete(m_semaphore);
+ m_semaphore = NULL;
+ }
+}
+
+/**
+ * Generic transaction.
+ *
+ * This is a lower-level interface to the I2C hardware giving you more control over each transaction.
+ *
+ * @param dataToSend Buffer of data to send as part of the transaction.
+ * @param sendSize Number of bytes to send as part of the transaction. [0..6]
+ * @param dataReceived Buffer to read data into.
+ * @param receiveSize Number of byted to read from the device. [0..7]
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::Transaction(UINT8 *dataToSend, UINT8 sendSize, UINT8 *dataReceived, UINT8 receiveSize)
+{
+ if (sendSize > 6)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "sendSize");
+ return true;
+ }
+ if (receiveSize > 7)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "receiveSize");
+ return true;
+ }
+
+ UINT32 data=0;
+ UINT32 dataHigh=0;
+ UINT32 i;
+ for(i=0; i<sendSize && i<sizeof(data); i++)
+ {
+ data |= (UINT32)dataToSend[i] << (8*i);
+ }
+ for(; i<sendSize; i++)
+ {
+ dataHigh |= (UINT32)dataToSend[i] << (8*(i-sizeof(data)));
+ }
+
+ bool aborted = true;
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ {
+ Synchronized sync(m_semaphore);
+ m_module->m_fpgaDIO->writeI2CConfig_Address(m_deviceAddress, &localStatus);
+ m_module->m_fpgaDIO->writeI2CConfig_BytesToWrite(sendSize, &localStatus);
+ m_module->m_fpgaDIO->writeI2CConfig_BytesToRead(receiveSize, &localStatus);
+ if (sendSize > 0) m_module->m_fpgaDIO->writeI2CDataToSend(data, &localStatus);
+ if (sendSize > sizeof(data)) m_module->m_fpgaDIO->writeI2CConfig_DataToSendHigh(dataHigh, &localStatus);
+ m_module->m_fpgaDIO->writeI2CConfig_BitwiseHandshake(m_compatibilityMode, &localStatus);
+ UINT8 transaction = m_module->m_fpgaDIO->readI2CStatus_Transaction(&localStatus);
+ m_module->m_fpgaDIO->strobeI2CStart(&localStatus);
+ while(transaction == m_module->m_fpgaDIO->readI2CStatus_Transaction(&localStatus)) taskDelay(1);
+ while(!m_module->m_fpgaDIO->readI2CStatus_Done(&localStatus)) taskDelay(1);
+ aborted = m_module->m_fpgaDIO->readI2CStatus_Aborted(&localStatus);
+ if (receiveSize > 0) data = m_module->m_fpgaDIO->readI2CDataReceived(&localStatus);
+ if (receiveSize > sizeof(data)) dataHigh = m_module->m_fpgaDIO->readI2CStatus_DataReceivedHigh(&localStatus);
+ }
+ wpi_setError(localStatus);
+
+ for(i=0; i<receiveSize && i<sizeof(data); i++)
+ {
+ dataReceived[i] = (data >> (8*i)) & 0xFF;
+ }
+ for(; i<receiveSize; i++)
+ {
+ dataReceived[i] = (dataHigh >> (8*(i-sizeof(data)))) & 0xFF;
+ }
+ return aborted;
+}
+
+/**
+ * Attempt to address a device on the I2C bus.
+ *
+ * This allows you to figure out if there is a device on the I2C bus that
+ * responds to the address specified in the constructor.
+ *
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::AddressOnly()
+{
+ return Transaction(NULL, 0, NULL, 0);
+}
+
+/**
+ * Execute a write transaction with the device.
+ *
+ * Write a single byte to a register on a device and wait until the
+ * transaction is complete.
+ *
+ * @param registerAddress The address of the register on the device to be written.
+ * @param data The byte to write to the register on the device.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::Write(UINT8 registerAddress, UINT8 data)
+{
+ UINT8 buffer[2];
+ buffer[0] = registerAddress;
+ buffer[1] = data;
+ return Transaction(buffer, sizeof(buffer), NULL, 0);
+}
+
+/**
+ * Execute a read transaction with the device.
+ *
+ * Read 1 to 7 bytes from a device.
+ * Most I2C devices will auto-increment the register pointer internally
+ * allowing you to read up to 7 consecutive registers on a device in a
+ * single transaction.
+ *
+ * @param registerAddress The register to read first in the transaction.
+ * @param count The number of bytes to read in the transaction. [1..7]
+ * @param buffer A pointer to the array of bytes to store the data read from the device.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::Read(UINT8 registerAddress, UINT8 count, UINT8 *buffer)
+{
+ if (count < 1 || count > 7)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+ return true;
+ }
+ if (buffer == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "buffer");
+ return true;
+ }
+
+ return Transaction(®isterAddress, sizeof(registerAddress), buffer, count);
+}
+
+/**
+ * Send a broadcast write to all devices on the I2C bus.
+ *
+ * This is not currently implemented!
+ *
+ * @param registerAddress The register to write on all devices on the bus.
+ * @param data The value to write to the devices.
+ */
+void I2C::Broadcast(UINT8 registerAddress, UINT8 data)
+{
+}
+
+/**
+ * SetCompatibilityMode
+ *
+ * Enables bitwise clock skewing detection. This will reduce the I2C interface speed,
+ * but will allow you to communicate with devices that skew the clock at abnormal times.
+ *
+ * @param enable Enable compatibility mode for this sensor or not.
+ */
+void I2C::SetCompatibilityMode(bool enable)
+{
+ m_compatibilityMode = enable;
+}
+
+/**
+ * Verify that a device's registers contain expected values.
+ *
+ * Most devices will have a set of registers that contain a known value that
+ * can be used to identify them. This allows an I2C device driver to easily
+ * verify that the device contains the expected value.
+ *
+ * @pre The device must support and be configured to use register auto-increment.
+ *
+ * @param registerAddress The base register to start reading from the device.
+ * @param count The size of the field to be verified.
+ * @param expected A buffer containing the values expected from the device.
+ */
+bool I2C::VerifySensor(UINT8 registerAddress, UINT8 count, const UINT8 *expected)
+{
+ // TODO: Make use of all 7 read bytes
+ UINT8 deviceData[4];
+ for (UINT8 i=0, curRegisterAddress = registerAddress; i < count; i+=4, curRegisterAddress+=4)
+ {
+ UINT8 toRead = count - i < 4 ? count - i : 4;
+ // Read the chunk of data. Return false if the sensor does not respond.
+ if (Read(curRegisterAddress, toRead, deviceData)) return false;
+
+ for (UINT8 j=0; j<toRead; j++)
+ {
+ if(deviceData[j] != expected[i + j]) return false;
+ }
+ }
+ return true;
+}
+
diff --git a/aos/externals/WPILib/WPILib/I2C.h b/aos/externals/WPILib/WPILib/I2C.h
new file mode 100644
index 0000000..d60c6bc
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/I2C.h
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef I2C_H
+#define I2C_H
+
+#include "SensorBase.h"
+
+class DigitalModule;
+
+/**
+ * I2C bus interface class.
+ *
+ * This class is intended to be used by sensor (and other I2C device) drivers.
+ * It probably should not be used directly.
+ *
+ * It is constructed by calling DigitalModule::GetI2C() on a DigitalModule object.
+ */
+class I2C : SensorBase
+{
+ friend class DigitalModule;
+public:
+ virtual ~I2C();
+ bool Transaction(UINT8 *dataToSend, UINT8 sendSize, UINT8 *dataReceived, UINT8 receiveSize);
+ bool AddressOnly();
+ bool Write(UINT8 registerAddress, UINT8 data);
+ bool Read(UINT8 registerAddress, UINT8 count, UINT8 *data);
+ void Broadcast(UINT8 registerAddress, UINT8 data);
+ void SetCompatibilityMode(bool enable);
+
+ bool VerifySensor(UINT8 registerAddress, UINT8 count, const UINT8 *expected);
+private:
+ static SEM_ID m_semaphore;
+ static UINT32 m_objCount;
+
+ I2C(DigitalModule *module, UINT8 deviceAddress);
+
+ DigitalModule *m_module;
+ UINT8 m_deviceAddress;
+ bool m_compatibilityMode;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/InterruptableSensorBase.cpp b/aos/externals/WPILib/WPILib/InterruptableSensorBase.cpp
new file mode 100644
index 0000000..4a72b07
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/InterruptableSensorBase.cpp
@@ -0,0 +1,98 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "InterruptableSensorBase.h"
+#include "Utility.h"
+
+InterruptableSensorBase::InterruptableSensorBase()
+{
+ m_manager = NULL;
+ m_interrupt = NULL;
+}
+
+InterruptableSensorBase::~InterruptableSensorBase()
+{
+
+}
+
+void InterruptableSensorBase::AllocateInterrupts(bool watcher)
+{
+ wpi_assert(m_interrupt == NULL);
+ wpi_assert(m_manager == NULL);
+ // Expects the calling leaf class to allocate an interrupt index.
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_interrupt = tInterrupt::create(m_interruptIndex, &localStatus);
+ m_interrupt->writeConfig_WaitForAck(false, &localStatus);
+ m_manager = new tInterruptManager(1 << m_interruptIndex, watcher, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Cancel interrupts on this device.
+ * This deallocates all the chipobject structures and disables any interrupts.
+ */
+void InterruptableSensorBase::CancelInterrupts()
+{
+ wpi_assert(m_manager != NULL);
+ wpi_assert(m_interrupt != NULL);
+ delete m_interrupt;
+ delete m_manager;
+ m_interrupt = NULL;
+ m_manager = NULL;
+}
+
+/**
+ * In synchronous mode, wait for the defined interrupt to occur.
+ * @param timeout Timeout in seconds
+ */
+void InterruptableSensorBase::WaitForInterrupt(float timeout)
+{
+ wpi_assert(m_manager != NULL);
+ wpi_assert(m_interrupt != NULL);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_manager->watch((INT32)(timeout * 1e3), &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Enable interrupts to occur on this input.
+ * Interrupts are disabled when the RequestInterrupt call is made. This gives time to do the
+ * setup of the other options before starting to field interrupts.
+ */
+void InterruptableSensorBase::EnableInterrupts()
+{
+ wpi_assert(m_manager != NULL);
+ wpi_assert(m_interrupt != NULL);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_manager->enable(&localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Disable Interrupts without without deallocating structures.
+ */
+void InterruptableSensorBase::DisableInterrupts()
+{
+ wpi_assert(m_manager != NULL);
+ wpi_assert(m_interrupt != NULL);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_manager->disable(&localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Return the timestamp for the interrupt that occurred most recently.
+ * This is in the same time domain as GetClock().
+ * @return Timestamp in seconds since boot.
+ */
+double InterruptableSensorBase::ReadInterruptTimestamp()
+{
+ wpi_assert(m_interrupt != NULL);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 timestamp = m_interrupt->readTimeStamp(&localStatus);
+ wpi_setError(localStatus);
+ return timestamp * 1e-6;
+}
diff --git a/aos/externals/WPILib/WPILib/InterruptableSensorBase.h b/aos/externals/WPILib/WPILib/InterruptableSensorBase.h
new file mode 100644
index 0000000..2743399
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/InterruptableSensorBase.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef INTERRUPTABLE_SENSORBASE_H_
+#define INTERRUPTABLE_SENSORBASE_H_
+
+#include "ChipObject.h"
+#include "SensorBase.h"
+
+class InterruptableSensorBase : public SensorBase
+{
+public:
+ InterruptableSensorBase();
+ virtual ~InterruptableSensorBase();
+ virtual void RequestInterrupts(tInterruptHandler handler, void *param) = 0; ///< Asynchronus handler version.
+ virtual void RequestInterrupts() = 0; ///< Synchronus Wait version.
+ virtual void CancelInterrupts(); ///< Free up the underlying chipobject functions.
+ virtual void WaitForInterrupt(float timeout); ///< Synchronus version.
+ virtual void EnableInterrupts(); ///< Enable interrupts - after finishing setup.
+ virtual void DisableInterrupts(); ///< Disable, but don't deallocate.
+ virtual double ReadInterruptTimestamp(); ///< Return the timestamp for the interrupt that occurred.
+protected:
+ tInterrupt *m_interrupt;
+ tInterruptManager *m_manager;
+ UINT32 m_interruptIndex;
+ void AllocateInterrupts(bool watcher);
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/IterativeRobot.cpp b/aos/externals/WPILib/WPILib/IterativeRobot.cpp
new file mode 100644
index 0000000..1dc7f81
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/IterativeRobot.cpp
@@ -0,0 +1,326 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "IterativeRobot.h"
+
+#include "DriverStation.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include <taskLib.h>
+
+const double IterativeRobot::kDefaultPeriod;
+
+/**
+ * Constructor for RobotIterativeBase
+ *
+ * The constructor initializes the instance variables for the robot to indicate
+ * the status of initialization for disabled, autonomous, and teleop code.
+ */
+IterativeRobot::IterativeRobot()
+ : m_disabledInitialized (false)
+ , m_autonomousInitialized (false)
+ , m_teleopInitialized (false)
+ , m_period (kDefaultPeriod)
+{
+ m_watchdog.SetEnabled(false);
+}
+
+/**
+ * Free the resources for a RobotIterativeBase class.
+ */
+IterativeRobot::~IterativeRobot()
+{
+}
+
+/**
+ * Set the period for the periodic functions.
+ *
+ * @param period The period of the periodic function calls. 0.0 means sync to driver station control data.
+ */
+void IterativeRobot::SetPeriod(double period)
+{
+ if (period > 0.0)
+ {
+ // Not syncing with the DS, so start the timer for the main loop
+ m_mainLoopTimer.Reset();
+ m_mainLoopTimer.Start();
+ }
+ else
+ {
+ // Syncing with the DS, don't need the timer
+ m_mainLoopTimer.Stop();
+ }
+ m_period = period;
+}
+
+/**
+ * Get the period for the periodic functions.
+ * Returns 0.0 if configured to syncronize with DS control data packets.
+ * @return Period of the periodic function calls
+ */
+double IterativeRobot::GetPeriod()
+{
+ return m_period;
+}
+
+/**
+ * Get the number of loops per second for the IterativeRobot
+ * @return Frequency of the periodic function calls
+ */
+double IterativeRobot::GetLoopsPerSec()
+{
+ // If syncing to the driver station, we don't know the rate,
+ // so guess something close.
+ if (m_period <= 0.0)
+ return 50.0;
+ return 1.0 / m_period;
+}
+
+/**
+ * Provide an alternate "main loop" via StartCompetition().
+ *
+ * This specific StartCompetition() implements "main loop" behavior like that of the FRC
+ * control system in 2008 and earlier, with a primary (slow) loop that is
+ * called periodically, and a "fast loop" (a.k.a. "spin loop") that is
+ * called as fast as possible with no delay between calls.
+ */
+void IterativeRobot::StartCompetition()
+{
+ nUsageReporting::report(nUsageReporting::kResourceType_Framework, nUsageReporting::kFramework_Iterative);
+
+ // first and one-time initialization
+ RobotInit();
+
+ // loop forever, calling the appropriate mode-dependent function
+ while (true)
+ {
+ // Call the appropriate function depending upon the current robot mode
+ if (IsDisabled())
+ {
+ // call DisabledInit() if we are now just entering disabled mode from
+ // either a different mode or from power-on
+ if(!m_disabledInitialized)
+ {
+ DisabledInit();
+ m_disabledInitialized = true;
+ // reset the initialization flags for the other modes
+ m_autonomousInitialized = false;
+ m_teleopInitialized = false;
+ }
+ if (NextPeriodReady())
+ {
+ FRC_NetworkCommunication_observeUserProgramDisabled();
+ DisabledPeriodic();
+ }
+ DisabledContinuous();
+ }
+ else if (IsAutonomous())
+ {
+ // call AutonomousInit() if we are now just entering autonomous mode from
+ // either a different mode or from power-on
+ if(!m_autonomousInitialized)
+ {
+ AutonomousInit();
+ m_autonomousInitialized = true;
+ // reset the initialization flags for the other modes
+ m_disabledInitialized = false;
+ m_teleopInitialized = false;
+ }
+ if (NextPeriodReady())
+ {
+ FRC_NetworkCommunication_observeUserProgramAutonomous();
+ AutonomousPeriodic();
+ }
+ AutonomousContinuous();
+ }
+ else
+ {
+ // call TeleopInit() if we are now just entering teleop mode from
+ // either a different mode or from power-on
+ if(!m_teleopInitialized)
+ {
+ TeleopInit();
+ m_teleopInitialized = true;
+ // reset the initialization flags for the other modes
+ m_disabledInitialized = false;
+ m_autonomousInitialized = false;
+ }
+ if (NextPeriodReady())
+ {
+ FRC_NetworkCommunication_observeUserProgramTeleop();
+ TeleopPeriodic();
+ }
+ TeleopContinuous();
+ }
+ }
+}
+
+/**
+ * Determine if the periodic functions should be called.
+ *
+ * If m_period > 0.0, call the periodic function every m_period as compared
+ * to Timer.Get(). If m_period == 0.0, call the periodic functions whenever
+ * a packet is received from the Driver Station, or about every 20ms.
+ *
+ * @todo Decide what this should do if it slips more than one cycle.
+ */
+
+bool IterativeRobot::NextPeriodReady()
+{
+ if (m_period > 0.0)
+ {
+ return m_mainLoopTimer.HasPeriodPassed(m_period);
+ }
+ else
+ {
+ return m_ds->IsNewControlData();
+ }
+}
+
+/**
+ * Robot-wide initialization code should go here.
+ *
+ * Users should override this method for default Robot-wide initialization which will
+ * be called when the robot is first powered on. It will be called exactly 1 time.
+ */
+void IterativeRobot::RobotInit()
+{
+ printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Initialization code for disabled mode should go here.
+ *
+ * Users should override this method for initialization code which will be called each time
+ * the robot enters disabled mode.
+ */
+void IterativeRobot::DisabledInit()
+{
+ printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Initialization code for autonomous mode should go here.
+ *
+ * Users should override this method for initialization code which will be called each time
+ * the robot enters autonomous mode.
+ */
+void IterativeRobot::AutonomousInit()
+{
+ printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Initialization code for teleop mode should go here.
+ *
+ * Users should override this method for initialization code which will be called each time
+ * the robot enters teleop mode.
+ */
+void IterativeRobot::TeleopInit()
+{
+ printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Periodic code for disabled mode should go here.
+ *
+ * Users should override this method for code which will be called periodically at a regular
+ * rate while the robot is in disabled mode.
+ */
+void IterativeRobot::DisabledPeriodic()
+{
+ static bool firstRun = true;
+ if (firstRun)
+ {
+ printf("Default %s() method... Overload me!\n", __FUNCTION__);
+ firstRun = false;
+ }
+ taskDelay(1);
+}
+
+/**
+ * Periodic code for autonomous mode should go here.
+ *
+ * Users should override this method for code which will be called periodically at a regular
+ * rate while the robot is in autonomous mode.
+ */
+void IterativeRobot::AutonomousPeriodic()
+{
+ static bool firstRun = true;
+ if (firstRun)
+ {
+ printf("Default %s() method... Overload me!\n", __FUNCTION__);
+ firstRun = false;
+ }
+ taskDelay(1);
+}
+
+/**
+ * Periodic code for teleop mode should go here.
+ *
+ * Users should override this method for code which will be called periodically at a regular
+ * rate while the robot is in teleop mode.
+ */
+void IterativeRobot::TeleopPeriodic()
+{
+ static bool firstRun = true;
+ if (firstRun)
+ {
+ printf("Default %s() method... Overload me!\n", __FUNCTION__);
+ firstRun = false;
+ }
+ taskDelay(1);
+}
+
+/**
+ * Continuous code for disabled mode should go here.
+ *
+ * Users should override this method for code which will be called repeatedly as frequently
+ * as possible while the robot is in disabled mode.
+ */
+void IterativeRobot::DisabledContinuous()
+{
+ static bool firstRun = true;
+ if (firstRun)
+ {
+ printf("Default %s() method... Overload me!\n", __FUNCTION__);
+ firstRun = false;
+ }
+ m_ds->WaitForData();
+}
+
+/**
+ * Continuous code for autonomous mode should go here.
+ *
+ * Users should override this method for code which will be called repeatedly as frequently
+ * as possible while the robot is in autonomous mode.
+ */
+void IterativeRobot::AutonomousContinuous()
+{
+ static bool firstRun = true;
+ if (firstRun)
+ {
+ printf("Default %s() method... Overload me!\n", __FUNCTION__);
+ firstRun = false;
+ }
+ m_ds->WaitForData();
+}
+
+/**
+ * Continuous code for teleop mode should go here.
+ *
+ * Users should override this method for code which will be called repeatedly as frequently
+ * as possible while the robot is in teleop mode.
+ */
+void IterativeRobot::TeleopContinuous()
+{
+ static bool firstRun = true;
+ if (firstRun)
+ {
+ printf("Default %s() method... Overload me!\n", __FUNCTION__);
+ firstRun = false;
+ }
+ m_ds->WaitForData();
+}
diff --git a/aos/externals/WPILib/WPILib/IterativeRobot.h b/aos/externals/WPILib/WPILib/IterativeRobot.h
new file mode 100644
index 0000000..cee0f64
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/IterativeRobot.h
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef ROBOT_ITERATIVE_H_
+#define ROBOT_ITERATIVE_H_
+
+#include "Timer.h"
+#include "RobotBase.h"
+
+/**
+ * IterativeRobot implements a specific type of Robot Program framework, extending the RobotBase class.
+ *
+ * The IterativeRobot class is intended to be subclassed by a user creating a robot program.
+ *
+ * This class is intended to implement the "old style" default code, by providing
+ * the following functions which are called by the main loop, StartCompetition(), at the appropriate times:
+ *
+ * RobotInit() -- provide for initialization at robot power-on
+ *
+ * Init() functions -- each of the following functions is called once when the
+ * appropriate mode is entered:
+ * - DisabledInit() -- called only when first disabled
+ * - AutonomousInit() -- called each and every time autonomous is entered from another mode
+ * - TeleopInit() -- called each and every time teleop is entered from another mode
+ *
+ * Periodic() functions -- each of these functions is called iteratively at the
+ * appropriate periodic rate (aka the "slow loop"). The default period of
+ * the iterative robot is synced to the driver station control packets,
+ * giving a periodic frequency of about 50Hz (50 times per second).
+ * - DisabledPeriodic()
+ * - AutonomousPeriodic()
+ * - TeleopPeriodic()
+ *
+ * Continuous() functions -- each of these functions is called repeatedly as
+ * fast as possible. These functions are generally discouraged
+ * and if they are used, they should contain a Wait() of some type:
+ * - DisabledContinuous()
+ * - AutonomousContinuous()
+ * - TeleopContinuous()
+ *
+ */
+
+class IterativeRobot : public RobotBase {
+public:
+ /*
+ * The default period for the periodic function calls (seconds)
+ * Setting the period to 0.0 will cause the periodic functions to follow
+ * the Driver Station packet rate of about 50Hz.
+ */
+ static const double kDefaultPeriod = 0.0;
+
+ virtual void StartCompetition();
+
+ virtual void RobotInit();
+ virtual void DisabledInit();
+ virtual void AutonomousInit();
+ virtual void TeleopInit();
+
+ virtual void DisabledPeriodic();
+ virtual void AutonomousPeriodic();
+ virtual void TeleopPeriodic();
+
+ virtual void DisabledContinuous();
+ virtual void AutonomousContinuous();
+ virtual void TeleopContinuous();
+
+ void SetPeriod(double period);
+ double GetPeriod();
+ double GetLoopsPerSec();
+
+protected:
+ virtual ~IterativeRobot();
+ IterativeRobot();
+
+private:
+ bool NextPeriodReady();
+
+ bool m_disabledInitialized;
+ bool m_autonomousInitialized;
+ bool m_teleopInitialized;
+ double m_period;
+ Timer m_mainLoopTimer;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Jaguar.cpp b/aos/externals/WPILib/WPILib/Jaguar.cpp
new file mode 100644
index 0000000..77f3c43
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Jaguar.cpp
@@ -0,0 +1,100 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+
+#include "Jaguar.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "DigitalModule.h"
+
+/**
+ * Common initialization code called by all constructors.
+ */
+void Jaguar::InitJaguar()
+{
+ /*
+ * Input profile defined by Luminary Micro.
+ *
+ * Full reverse ranges from 0.671325ms to 0.6972211ms
+ * Proportional reverse ranges from 0.6972211ms to 1.4482078ms
+ * Neutral ranges from 1.4482078ms to 1.5517922ms
+ * Proportional forward ranges from 1.5517922ms to 2.3027789ms
+ * Full forward ranges from 2.3027789ms to 2.328675ms
+ * TODO: compute the appropriate values based on digital loop timing
+ */
+ SetBounds(251, 135, 128, 120, 4);
+ SetPeriodMultiplier(kPeriodMultiplier_1X);
+ SetRaw(m_centerPwm);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Jaguar, GetChannel(), GetModuleNumber() - 1);
+}
+
+/**
+ * Constructor that assumes the default digital module.
+ *
+ * @param channel The PWM channel on the digital module that the Jaguar is attached to.
+ */
+Jaguar::Jaguar(UINT32 channel) : SafePWM(channel)
+{
+ InitJaguar();
+}
+
+/**
+ * Constructor that specifies the digital module.
+ *
+ * @param moduleNumber The digital module (1 or 2).
+ * @param channel The PWM channel on the digital module that the Jaguar is attached to.
+ */
+Jaguar::Jaguar(UINT8 moduleNumber, UINT32 channel) : SafePWM(moduleNumber, channel)
+{
+ InitJaguar();
+}
+
+Jaguar::~Jaguar()
+{
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ * @param syncGroup Unused interface.
+ */
+void Jaguar::Set(float speed, UINT8 syncGroup)
+{
+ SetSpeed(speed);
+}
+
+/**
+ * Get the recently set value of the PWM.
+ *
+ * @return The most recently set value for the PWM between -1.0 and 1.0.
+ */
+float Jaguar::Get()
+{
+ return GetSpeed();
+}
+
+/**
+ * Common interface for disabling a motor.
+ */
+void Jaguar::Disable()
+{
+ SetRaw(kPwmDisabled);
+}
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @param output Write out the PWM value as was found in the PIDController
+ */
+void Jaguar::PIDWrite(float output)
+{
+ Set(output);
+}
+
diff --git a/aos/externals/WPILib/WPILib/Jaguar.h b/aos/externals/WPILib/WPILib/Jaguar.h
new file mode 100644
index 0000000..e8691d6
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Jaguar.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef JAGUAR_H
+#define JAGUAR_H
+
+#include "SafePWM.h"
+#include "SpeedController.h"
+#include "PIDOutput.h"
+
+/**
+ * Luminary Micro Jaguar Speed Control
+ */
+class Jaguar : public SafePWM, public SpeedController, public PIDOutput
+{
+public:
+ explicit Jaguar(UINT32 channel);
+ Jaguar(UINT8 moduleNumber, UINT32 channel);
+ virtual ~Jaguar();
+ virtual void Set(float value, UINT8 syncGroup=0);
+ virtual float Get();
+ virtual void Disable();
+
+ virtual void PIDWrite(float output);
+
+private:
+ void InitJaguar();
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Joystick.cpp b/aos/externals/WPILib/WPILib/Joystick.cpp
new file mode 100644
index 0000000..c2c2d51
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Joystick.cpp
@@ -0,0 +1,302 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Joystick.h"
+#include "DriverStation.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+#include <math.h>
+
+const UINT32 Joystick::kDefaultXAxis;
+const UINT32 Joystick::kDefaultYAxis;
+const UINT32 Joystick::kDefaultZAxis;
+const UINT32 Joystick::kDefaultTwistAxis;
+const UINT32 Joystick::kDefaultThrottleAxis;
+const UINT32 Joystick::kDefaultTriggerButton;
+const UINT32 Joystick::kDefaultTopButton;
+static Joystick *joysticks[DriverStation::kJoystickPorts];
+static bool joySticksInitialized = false;
+
+/**
+ * Construct an instance of a joystick.
+ * The joystick index is the usb port on the drivers station.
+ *
+ * @param port The port on the driver station that the joystick is plugged into.
+ */
+Joystick::Joystick(UINT32 port)
+ : m_ds (NULL)
+ , m_port (port)
+ , m_axes (NULL)
+ , m_buttons (NULL)
+{
+ InitJoystick(kNumAxisTypes, kNumButtonTypes);
+
+ m_axes[kXAxis] = kDefaultXAxis;
+ m_axes[kYAxis] = kDefaultYAxis;
+ m_axes[kZAxis] = kDefaultZAxis;
+ m_axes[kTwistAxis] = kDefaultTwistAxis;
+ m_axes[kThrottleAxis] = kDefaultThrottleAxis;
+
+ m_buttons[kTriggerButton] = kDefaultTriggerButton;
+ m_buttons[kTopButton] = kDefaultTopButton;
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Joystick, port);
+}
+
+/**
+ * Version of the constructor to be called by sub-classes.
+ *
+ * This constructor allows the subclass to configure the number of constants
+ * for axes and buttons.
+ *
+ * @param port The port on the driver station that the joystick is plugged into.
+ * @param numAxisTypes The number of axis types in the enum.
+ * @param numButtonTypes The number of button types in the enum.
+ */
+Joystick::Joystick(UINT32 port, UINT32 numAxisTypes, UINT32 numButtonTypes)
+ : m_ds (NULL)
+ , m_port (port)
+ , m_axes (NULL)
+ , m_buttons (NULL)
+{
+ InitJoystick(numAxisTypes, numButtonTypes);
+}
+
+void Joystick::InitJoystick(UINT32 numAxisTypes, UINT32 numButtonTypes)
+{
+ if ( !joySticksInitialized )
+ {
+ for (unsigned i = 0; i < DriverStation::kJoystickPorts; i++)
+ joysticks[i] = NULL;
+ joySticksInitialized = true;
+ }
+ joysticks[m_port - 1] = this;
+
+ m_ds = DriverStation::GetInstance();
+ m_axes = new UINT32[numAxisTypes];
+ m_buttons = new UINT32[numButtonTypes];
+}
+
+Joystick * Joystick::GetStickForPort(UINT32 port)
+{
+ Joystick *stick = joysticks[port - 1];
+ if (stick == NULL)
+ {
+ stick = new Joystick(port);
+ joysticks[port - 1] = stick;
+ }
+ return stick;
+}
+
+Joystick::~Joystick()
+{
+ delete [] m_buttons;
+ delete [] m_axes;
+}
+
+/**
+ * Get the X value of the joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+float Joystick::GetX(JoystickHand hand)
+{
+ return GetRawAxis(m_axes[kXAxis]);
+}
+
+/**
+ * Get the Y value of the joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+float Joystick::GetY(JoystickHand hand)
+{
+ return GetRawAxis(m_axes[kYAxis]);
+}
+
+/**
+ * Get the Z value of the current joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+float Joystick::GetZ()
+{
+ return GetRawAxis(m_axes[kZAxis]);
+}
+
+/**
+ * Get the twist value of the current joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+float Joystick::GetTwist()
+{
+ return GetRawAxis(m_axes[kTwistAxis]);
+}
+
+/**
+ * Get the throttle value of the current joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+float Joystick::GetThrottle()
+{
+ return GetRawAxis(m_axes[kThrottleAxis]);
+}
+
+/**
+ * Get the value of the axis.
+ *
+ * @param axis The axis to read [1-6].
+ * @return The value of the axis.
+ */
+float Joystick::GetRawAxis(UINT32 axis)
+{
+ return m_ds->GetStickAxis(m_port, axis);
+}
+
+/**
+ * For the current joystick, return the axis determined by the argument.
+ *
+ * This is for cases where the joystick axis is returned programatically, otherwise one of the
+ * previous functions would be preferable (for example GetX()).
+ *
+ * @param axis The axis to read.
+ * @return The value of the axis.
+ */
+float Joystick::GetAxis(AxisType axis)
+{
+ switch(axis)
+ {
+ case kXAxis: return this->GetX();
+ case kYAxis: return this->GetY();
+ case kZAxis: return this->GetZ();
+ case kTwistAxis: return this->GetTwist();
+ case kThrottleAxis: return this->GetThrottle();
+ default:
+ wpi_setWPIError(BadJoystickAxis);
+ return 0.0;
+ }
+}
+
+/**
+ * Read the state of the trigger on the joystick.
+ *
+ * Look up which button has been assigned to the trigger and read its state.
+ *
+ * @param hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface.
+ * @return The state of the trigger.
+ */
+bool Joystick::GetTrigger(JoystickHand hand)
+{
+ return GetRawButton(m_buttons[kTriggerButton]);
+}
+
+/**
+ * Read the state of the top button on the joystick.
+ *
+ * Look up which button has been assigned to the top and read its state.
+ *
+ * @param hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface.
+ * @return The state of the top button.
+ */
+bool Joystick::GetTop(JoystickHand hand)
+{
+ return GetRawButton(m_buttons[kTopButton]);
+}
+
+/**
+ * This is not supported for the Joystick.
+ * This method is only here to complete the GenericHID interface.
+ */
+bool Joystick::GetBumper(JoystickHand hand)
+{
+ // Joysticks don't have bumpers.
+ return false;
+}
+
+/**
+ * Get the button value for buttons 1 through 12.
+ *
+ * The buttons are returned in a single 16 bit value with one bit representing the state
+ * of each button. The appropriate button is returned as a boolean value.
+ *
+ * @param button The button number to be read.
+ * @return The state of the button.
+ **/
+bool Joystick::GetRawButton(UINT32 button)
+{
+ return ((0x1 << (button-1)) & m_ds->GetStickButtons(m_port)) != 0;
+}
+
+/**
+ * Get buttons based on an enumerated type.
+ *
+ * The button type will be looked up in the list of buttons and then read.
+ *
+ * @param button The type of button to read.
+ * @return The state of the button.
+ */
+bool Joystick::GetButton(ButtonType button)
+{
+ switch (button)
+ {
+ case kTriggerButton: return GetTrigger();
+ case kTopButton: return GetTop();
+ default:
+ return false;
+ }
+}
+
+/**
+ * Get the channel currently associated with the specified axis.
+ *
+ * @param axis The axis to look up the channel for.
+ * @return The channel fr the axis.
+ */
+UINT32 Joystick::GetAxisChannel(AxisType axis)
+{
+ return m_axes[axis];
+}
+
+/**
+ * Set the channel associated with a specified axis.
+ *
+ * @param axis The axis to set the channel for.
+ * @param channel The channel to set the axis to.
+ */
+void Joystick::SetAxisChannel(AxisType axis, UINT32 channel)
+{
+ m_axes[axis] = channel;
+}
+
+/**
+ * Get the magnitude of the direction vector formed by the joystick's
+ * current position relative to its origin
+ *
+ * @return The magnitude of the direction vector
+ */
+float Joystick::GetMagnitude(){
+ return sqrt(pow(GetX(),2) + pow(GetY(),2) );
+}
+
+/**
+ * Get the direction of the vector formed by the joystick and its origin
+ * in radians
+ *
+ * @return The direction of the vector in radians
+ */
+float Joystick::GetDirectionRadians(){
+ return atan2(GetX(), -GetY());
+}
+
+/**
+ * Get the direction of the vector formed by the joystick and its origin
+ * in degrees
+ *
+ * uses acos(-1) to represent Pi due to absence of readily accessable Pi
+ * constant in C++
+ *
+ * @return The direction of the vector in degrees
+ */
+float Joystick::GetDirectionDegrees(){
+ return (180/acos(-1))*GetDirectionRadians();
+}
diff --git a/aos/externals/WPILib/WPILib/Joystick.h b/aos/externals/WPILib/WPILib/Joystick.h
new file mode 100644
index 0000000..f600d24
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Joystick.h
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef JOYSTICK_H_
+#define JOYSTICK_H_
+
+#include "GenericHID.h"
+#include "ErrorBase.h"
+
+class DriverStation;
+
+/**
+ * Handle input from standard Joysticks connected to the Driver Station.
+ * This class handles standard input that comes from the Driver Station. Each time a value is requested
+ * the most recent value is returned. There is a single class instance for each joystick and the mapping
+ * of ports to hardware buttons depends on the code in the driver station.
+ */
+class Joystick : public GenericHID, public ErrorBase
+{
+public:
+ static const UINT32 kDefaultXAxis = 1;
+ static const UINT32 kDefaultYAxis = 2;
+ static const UINT32 kDefaultZAxis = 3;
+ static const UINT32 kDefaultTwistAxis = 4;
+ static const UINT32 kDefaultThrottleAxis = 3;
+ typedef enum
+ {
+ kXAxis, kYAxis, kZAxis, kTwistAxis, kThrottleAxis, kNumAxisTypes
+ } AxisType;
+ static const UINT32 kDefaultTriggerButton = 1;
+ static const UINT32 kDefaultTopButton = 2;
+ typedef enum
+ {
+ kTriggerButton, kTopButton, kNumButtonTypes
+ } ButtonType;
+
+ explicit Joystick(UINT32 port);
+ Joystick(UINT32 port, UINT32 numAxisTypes, UINT32 numButtonTypes);
+ virtual ~Joystick();
+
+ UINT32 GetAxisChannel(AxisType axis);
+ void SetAxisChannel(AxisType axis, UINT32 channel);
+
+ virtual float GetX(JoystickHand hand = kRightHand);
+ virtual float GetY(JoystickHand hand = kRightHand);
+ virtual float GetZ();
+ virtual float GetTwist();
+ virtual float GetThrottle();
+ virtual float GetAxis(AxisType axis);
+ float GetRawAxis(UINT32 axis);
+
+ virtual bool GetTrigger(JoystickHand hand = kRightHand);
+ virtual bool GetTop(JoystickHand hand = kRightHand);
+ virtual bool GetBumper(JoystickHand hand = kRightHand);
+ virtual bool GetButton(ButtonType button);
+ bool GetRawButton(UINT32 button);
+ static Joystick* GetStickForPort(UINT32 port);
+
+ virtual float GetMagnitude();
+ virtual float GetDirectionRadians();
+ virtual float GetDirectionDegrees();
+
+private:
+ DISALLOW_COPY_AND_ASSIGN(Joystick);
+ void InitJoystick(UINT32 numAxisTypes, UINT32 numButtonTypes);
+
+ DriverStation *m_ds;
+ UINT32 m_port;
+ UINT32 *m_axes;
+ UINT32 *m_buttons;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Kinect.cpp b/aos/externals/WPILib/WPILib/Kinect.cpp
new file mode 100644
index 0000000..838d782
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Kinect.cpp
@@ -0,0 +1,195 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Kinect.h"
+
+#include "DriverStation.h"
+#include "NetworkCommunication/FRCComm.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Skeleton.h"
+#include "Synchronized.h"
+#include "WPIErrors.h"
+
+#define kHeaderBundleID kFRC_NetworkCommunication_DynamicType_Kinect_Header
+#define kSkeletonExtraBundleID kFRC_NetworkCommunication_DynamicType_Kinect_Extra1
+#define kSkeletonBundleID kFRC_NetworkCommunication_DynamicType_Kinect_Vertices1
+
+Kinect *Kinect::_instance = NULL;
+
+Kinect::Kinect() :
+ m_recentPacketNumber(0),
+ m_numberOfPlayers(0)
+{
+ AddToSingletonList();
+ m_dataLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Kinect, 0);
+}
+
+Kinect::~Kinect()
+{
+ semTake(m_dataLock, WAIT_FOREVER);
+ semDelete(m_dataLock);
+}
+
+/**
+ * Get the one and only Kinect object
+ * @returns pointer to a Kinect
+ */
+Kinect *Kinect::GetInstance()
+{
+ if (_instance == NULL)
+ _instance = new Kinect();
+ return _instance;
+}
+
+/**
+ * Get the number of tracked players on the Kinect
+ * @return the number of players being actively tracked
+ */
+int Kinect::GetNumberOfPlayers()
+{
+ UpdateData();
+ return m_numberOfPlayers;
+}
+
+/**
+ * Get the floor clip plane as defined in the Kinect SDK
+ * @return The floor clip plane
+ */
+Kinect::Point4 Kinect::GetFloorClipPlane()
+{
+ UpdateData();
+ return m_floorClipPlane;
+}
+
+/**
+ * Get the gravity normal from the kinect as defined in the Kinect SDK
+ * @return The gravity normal (w is ignored)
+ */
+Kinect::Point4 Kinect::GetGravityNormal()
+{
+ UpdateData();
+ return m_gravityNormal;
+}
+
+/**
+ * Get the skeleton data
+ * Returns the detected skeleton data from the kinect as defined in the Kinect SDK
+ * @param skeletonIndex Which of (potentially 2) skeletons to return. This is ignored in this implementation and
+ * only a single skeleton is supported for the FRC release default gesture interpretation.
+ * @return The current version of the skeleton object.
+ */
+Skeleton Kinect::GetSkeleton(int skeletonIndex)
+{
+ if (skeletonIndex <= 0 || skeletonIndex > kNumSkeletons)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "Skeleton index must be 1");
+ return Skeleton();
+ }
+ UpdateData();
+ return m_skeletons[skeletonIndex-1];
+}
+
+/**
+ * Get the current position of the skeleton
+ * @param skeletonIndex the skeleton to read from
+ * @return the current position as defined in the Kinect SDK (w is ignored)
+ */
+Kinect::Point4 Kinect::GetPosition(int skeletonIndex)
+{
+ if (skeletonIndex <= 0 || skeletonIndex > kNumSkeletons)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "Skeleton index must be 1");
+ return Point4();
+ }
+ UpdateData();
+ return m_position[skeletonIndex-1];
+}
+
+/**
+ * Get the quality of the skeleton.
+ * Quality masks are defined in the SkeletonQuality enum
+ * @param skeletonIndex the skeleton to read from
+ * @return the quality value as defined in the Kinect SDK
+ */
+UINT32 Kinect::GetQuality(int skeletonIndex)
+{
+ if (skeletonIndex <= 0 || skeletonIndex > kNumSkeletons)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "Skeleton index must be 1");
+ return kClippedRight | kClippedLeft | kClippedTop | kClippedBottom;
+ }
+ UpdateData();
+ return m_quality[skeletonIndex-1];
+}
+
+/**
+ * Get the TrackingState of the skeleton.
+ * Tracking states are defined in the SkeletonTrackingState enum
+ * @param skeletonIndex the skeleton to read from
+ * @return the tracking state value as defined in the Kinect SDK
+ */
+Kinect::SkeletonTrackingState Kinect::GetTrackingState(int skeletonIndex)
+{
+ if (skeletonIndex <= 0 || skeletonIndex > kNumSkeletons)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "Skeleton index must be 1");
+ return kNotTracked;
+ }
+ UpdateData();
+ return m_trackingState[skeletonIndex-1];
+}
+
+/**
+ * Check for an update of new data from the Driver Station
+ * This will read the new values and update the data structures in this class.
+ */
+void Kinect::UpdateData()
+{
+ Synchronized sync(m_dataLock);
+ UINT32 packetNumber = DriverStation::GetInstance()->GetPacketNumber();
+ if (m_recentPacketNumber != packetNumber)
+ {
+ m_recentPacketNumber = packetNumber;
+ int retVal = getDynamicControlData(kHeaderBundleID, m_rawHeader, sizeof(m_rawHeader), 5);
+ if(retVal == 0)
+ {
+ m_numberOfPlayers = (int)m_rawHeader[13];
+ memcpy(&m_floorClipPlane.x, &m_rawHeader[18], 4);
+ memcpy(&m_floorClipPlane.y, &m_rawHeader[22], 4);
+ memcpy(&m_floorClipPlane.z, &m_rawHeader[26], 4);
+ memcpy(&m_floorClipPlane.w, &m_rawHeader[30], 4);
+ memcpy(&m_gravityNormal.x, &m_rawHeader[34], 4);
+ memcpy(&m_gravityNormal.y, &m_rawHeader[38], 4);
+ memcpy(&m_gravityNormal.z, &m_rawHeader[42], 4);
+ }
+
+ retVal = getDynamicControlData(kSkeletonExtraBundleID, m_rawSkeletonExtra, sizeof(m_rawSkeletonExtra), 5);
+ if(retVal == 0)
+ {
+ memcpy(&m_position[0].x, &m_rawSkeletonExtra[22], 4);
+ memcpy(&m_position[0].y, &m_rawSkeletonExtra[26], 4);
+ memcpy(&m_position[0].z, &m_rawSkeletonExtra[30], 4);
+ memcpy(&m_quality[0], &m_rawSkeletonExtra[34], 4);
+ memcpy(&m_trackingState[0], &m_rawSkeletonExtra[38], 4);
+ }
+
+ retVal = getDynamicControlData(kSkeletonBundleID, m_rawSkeleton, sizeof(m_rawSkeleton), 5);
+ if(retVal == 0)
+ {
+ for(int i=0; i < Skeleton::JointCount; i++)
+ {
+ memcpy(&m_skeletons[0].m_joints[i].x, &m_rawSkeleton[i*12+2], 4);
+ memcpy(&m_skeletons[0].m_joints[i].y, &m_rawSkeleton[i*12+6], 4);
+ memcpy(&m_skeletons[0].m_joints[i].z, &m_rawSkeleton[i*12+10], 4);
+ m_skeletons[0].m_joints[i].trackingState = (Skeleton::JointTrackingState)m_rawSkeletonExtra[i+2];
+ }
+ }
+
+ // TODO: Read skeleton #2
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/Kinect.h b/aos/externals/WPILib/WPILib/Kinect.h
new file mode 100644
index 0000000..cf8a4e0
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Kinect.h
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __KINECT_H__
+#define __KINECT_H__
+
+#include "SensorBase.h"
+#include "Skeleton.h"
+
+#include <semLib.h>
+
+#define kNumSkeletons 1
+
+/**
+ * Handles raw data input from the FRC Kinect Server
+ * when used with a Kinect device connected to the Driver Station.
+ * Each time a value is requested the most recent value is returned.
+ * See Getting Started with Microsoft Kinect for FRC and the Kinect
+ * for Windows SDK API reference for more information
+ */
+class Kinect : public SensorBase
+{
+public:
+ typedef enum {kNotTracked, kPositionOnly, kTracked} SkeletonTrackingState;
+ typedef enum {kClippedRight = 1, kClippedLeft = 2, kClippedTop = 4, kClippedBottom = 8} SkeletonQuality;
+ typedef struct
+ {
+ float x;
+ float y;
+ float z;
+ float w;
+ } Point4;
+
+ int GetNumberOfPlayers();
+ Point4 GetFloorClipPlane();
+ Point4 GetGravityNormal();
+ Skeleton GetSkeleton(int skeletonIndex = 1);
+ Point4 GetPosition(int skeletonIndex = 1);
+ UINT32 GetQuality(int skeletonIndex = 1);
+ SkeletonTrackingState GetTrackingState(int skeletonIndex = 1);
+
+ static Kinect *GetInstance();
+
+private:
+ Kinect();
+ ~Kinect();
+ void UpdateData();
+
+ DISALLOW_COPY_AND_ASSIGN(Kinect);
+
+ UINT32 m_recentPacketNumber;
+ SEM_ID m_dataLock;
+ int m_numberOfPlayers;
+ Point4 m_floorClipPlane;
+ Point4 m_gravityNormal;
+ Point4 m_position[kNumSkeletons];
+ UINT32 m_quality[kNumSkeletons];
+ SkeletonTrackingState m_trackingState[kNumSkeletons];
+ Skeleton m_skeletons[kNumSkeletons];
+
+ // TODO: Include structs for this data format (would be clearer than 100 magic numbers)
+ char m_rawHeader[46];
+ char m_rawSkeletonExtra[42];
+ char m_rawSkeleton[242];
+
+ static Kinect *_instance;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/KinectStick.cpp b/aos/externals/WPILib/WPILib/KinectStick.cpp
new file mode 100644
index 0000000..86fb6a4
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/KinectStick.cpp
@@ -0,0 +1,201 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "KinectStick.h"
+
+#include "DriverStation.h"
+#include "Joystick.h"
+#include "NetworkCommunication/FRCComm.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+UINT32 KinectStick::_recentPacketNumber = 0;
+KinectStick::KinectStickData KinectStick::_sticks;
+
+#define kJoystickBundleID kFRC_NetworkCommunication_DynamicType_Kinect_Joystick
+#define kTriggerMask 1
+#define kTopMask 2
+
+/**
+ * Kinect joystick constructor
+ * @param id value is either 1 or 2 for the left or right joystick decoded from
+ * gestures interpreted by the Kinect server on the Driver Station computer.
+ */
+KinectStick::KinectStick(int id)
+{
+ if (id != 1 && id != 2)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "KinectStick ID must be 1 or 2");
+ return;
+ }
+ m_id = id;
+
+ nUsageReporting::report(nUsageReporting::kResourceType_KinectStick, id);
+}
+
+/**
+ * Get the X value of the KinectStick. This axis
+ * is unimplemented in the default gestures but can
+ * be populated by teams editing the Kinect Server.
+ * @param hand Unused
+ * @return The X value of the KinectStick
+ */
+float KinectStick::GetX(JoystickHand hand)
+{
+ return GetRawAxis(Joystick::kDefaultXAxis);
+}
+
+/**
+ * Get the Y value of the KinectStick. This axis
+ * represents arm angle in the default gestures
+ * @param hand Unused
+ * @return The Y value of the KinectStick
+ */
+float KinectStick::GetY(JoystickHand hand)
+{
+ return GetRawAxis(Joystick::kDefaultYAxis);
+}
+
+/**
+ * Get the Z value of the KinectStick. This axis
+ * is unimplemented in the default gestures but can
+ * be populated by teams editing the Kinect Server.
+ * @param hand Unused
+ * @return The Z value of the KinectStick
+ */
+float KinectStick::GetZ()
+{
+ return GetRawAxis(Joystick::kDefaultZAxis);
+}
+
+/**
+ * Get the Twist value of the KinectStick. This axis
+ * is unimplemented in the default gestures but can
+ * be populated by teams editing the Kinect Server.
+ * @return The Twist value of the KinectStick
+ */
+float KinectStick::GetTwist()
+{
+ return GetRawAxis(Joystick::kDefaultTwistAxis);
+}
+
+/**
+ * Get the Throttle value of the KinectStick. This axis
+ * is unimplemented in the default gestures but can
+ * be populated by teams editing the Kinect Server.
+ * @return The Throttle value of the KinectStick
+ */
+float KinectStick::GetThrottle()
+{
+ return GetRawAxis(Joystick::kDefaultThrottleAxis);
+}
+
+/**
+ * Get the value of the KinectStick axis.
+ *
+ * @param axis The axis to read [1-6].
+ * @return The value of the axis
+ */
+float KinectStick::GetRawAxis(UINT32 axis)
+{
+ if (StatusIsFatal()) return 0.0;
+
+ GetData();
+ float value = ConvertRawToFloat(_sticks.formatted.rawSticks[m_id - 1].axis[axis-1]);
+ return value;
+}
+
+/**
+ * Get the button value for the button set as the default trigger
+ *
+ * @param hand Unused
+ * @return The state of the button.
+ */
+bool KinectStick::GetTrigger(JoystickHand hand)
+{
+ return GetRawButton(kTriggerMask);
+}
+
+/**
+ * Get the button value for the button set as the default top
+ *
+ * @param hand Unused
+ * @return The state of the button.
+ */
+bool KinectStick::GetTop(JoystickHand hand)
+{
+ return GetRawButton(kTopMask);
+}
+
+/**
+ * Get the button value for the button set as the default bumper (button 4)
+ *
+ * @param hand Unused
+ * @return The state of the button.
+ */
+bool KinectStick::GetBumper(JoystickHand hand)
+{
+ // TODO: Should this even be in GenericHID? Is 4 an appropriate mask value (button 3)?
+ return GetRawButton(4);
+}
+
+/**
+ * Get the button value for buttons 1 through 12. The default gestures
+ * implement only 9 buttons.
+ *
+ * The appropriate button is returned as a boolean value.
+ *
+ * @param button The button number to be read.
+ * @return The state of the button.
+ */
+bool KinectStick::GetRawButton(UINT32 button)
+{
+ if (StatusIsFatal()) return false;
+
+ GetData();
+ return (_sticks.formatted.rawSticks[m_id - 1].buttons & (1 << button)) != 0;
+}
+
+/**
+ * Get dynamic data from the driver station buffer
+ */
+void KinectStick::GetData()
+{
+ UINT32 packetNumber = DriverStation::GetInstance()->GetPacketNumber();
+ if (_recentPacketNumber != packetNumber)
+ {
+ _recentPacketNumber = packetNumber;
+ int retVal = getDynamicControlData(kJoystickBundleID, _sticks.data, sizeof(_sticks.data), 5);
+ if (retVal == 0)
+ {
+ wpi_assert(_sticks.formatted.size == sizeof(_sticks.data) - 1);
+ }
+ }
+}
+
+/**
+ * Convert an 8 bit joystick value to a floating point (-1,1) value
+ * @param value The 8 bit raw joystick value returned from the driver station
+ */
+float KinectStick::ConvertRawToFloat(INT8 value)
+{
+ float result;
+
+ if (value < 0)
+ result = ((float) value) / 128.0;
+ else
+ result = ((float) value) / 127.0;
+
+ wpi_assert(result <= 1.0 && result >= -1.0);
+
+ if (result > 1.0)
+ result = 1.0;
+ else if (result < -1.0)
+ result = -1.0;
+
+ return result;
+}
diff --git a/aos/externals/WPILib/WPILib/KinectStick.h b/aos/externals/WPILib/WPILib/KinectStick.h
new file mode 100644
index 0000000..ffa27ce
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/KinectStick.h
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __KINECT_STICK_H__
+#define __KINECT_STICK_H__
+
+#include "ErrorBase.h"
+#include "GenericHID.h"
+
+/**
+ * Handles input from the Joystick data sent by the FRC Kinect Server
+ * when used with a Kinect device connected to the Driver Station.
+ * Each time a value is requested the most recent value is returned.
+ * Default gestures embedded in the FRC Kinect Server are described
+ * in the document Getting Started with Microsoft Kinect for FRC.
+ */
+class KinectStick : public GenericHID, public ErrorBase
+{
+public:
+ explicit KinectStick(int id);
+ virtual float GetX(JoystickHand hand = kRightHand);
+ virtual float GetY(JoystickHand hand = kRightHand);
+ virtual float GetZ();
+ virtual float GetTwist();
+ virtual float GetThrottle();
+ virtual float GetRawAxis(UINT32 axis);
+
+ virtual bool GetTrigger(JoystickHand hand = kRightHand);
+ virtual bool GetTop(JoystickHand hand = kRightHand);
+ virtual bool GetBumper(JoystickHand hand = kRightHand);
+ virtual bool GetRawButton(UINT32 button);
+
+private:
+ void GetData();
+ float ConvertRawToFloat(INT8 charValue);
+
+ typedef union
+ {
+ struct
+ {
+ UINT8 size;
+ UINT8 id;
+ struct
+ {
+ unsigned char axis[6];
+ unsigned short buttons;
+ } rawSticks[2];
+ } formatted;
+ char data[18];
+ } KinectStickData;
+
+ int m_id;
+ static UINT32 _recentPacketNumber;
+ static KinectStickData _sticks;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Module.cpp b/aos/externals/WPILib/WPILib/Module.cpp
new file mode 100644
index 0000000..99e26ea
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Module.cpp
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Module.h"
+#include "AnalogModule.h"
+#include "DigitalModule.h"
+//#include "SolenoidModule.h"
+
+Module* Module::m_modules[kMaxModules] = {NULL};
+
+/**
+ * Constructor.
+ *
+ * @param type The type of module represented.
+ * @param number The module index within the module type.
+ */
+Module::Module(nLoadOut::tModuleType type, UINT8 number)
+ : m_moduleType (type)
+ , m_moduleNumber (number)
+{
+ m_modules[ToIndex(type, number)] = this;
+}
+
+/**
+ * Destructor.
+ */
+Module::~Module()
+{
+}
+
+/**
+ * Static module singleton factory.
+ *
+ * @param type The type of module represented.
+ * @param number The module index within the module type.
+ */
+Module* Module::GetModule(nLoadOut::tModuleType type, UINT8 number)
+{
+ if (m_modules[ToIndex(type, number)] == NULL)
+ {
+ switch(type)
+ {
+ case nLoadOut::kModuleType_Analog:
+ new AnalogModule(number);
+ break;
+ case nLoadOut::kModuleType_Digital:
+ new DigitalModule(number);
+ break;
+/*
+ case nLoadOut::kModuleType_Solenoid:
+ new SolenoidModule(number);
+ break;
+*/
+ default:
+ return NULL;
+ }
+ }
+ return m_modules[ToIndex(type, number)];
+}
+
+/**
+ * Create an index into the m_modules array based on type and number
+ *
+ * @param type The type of module represented.
+ * @param number The module index within the module type.
+ * @return The index into m_modules.
+ */
+UINT8 Module::ToIndex(nLoadOut::tModuleType type, UINT8 number)
+{
+ if (number == 0 || number > kMaxModuleNumber) return 0;
+ if (type < nLoadOut::kModuleType_Analog || type > nLoadOut::kModuleType_Solenoid) return 0;
+ return (type * kMaxModuleNumber) + (number - 1);
+}
diff --git a/aos/externals/WPILib/WPILib/Module.h b/aos/externals/WPILib/WPILib/Module.h
new file mode 100644
index 0000000..1c9f976
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Module.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef MODULE_H_
+#define MODULE_H_
+
+#include "SensorBase.h"
+#include "NetworkCommunication/LoadOut.h"
+
+#define kMaxModules (nLoadOut::kModuleType_Solenoid * kMaxModuleNumber + (kMaxModuleNumber - 1))
+
+class Module: public SensorBase
+{
+public:
+ nLoadOut::tModuleType GetType() {return m_moduleType;}
+ UINT8 GetNumber() {return m_moduleNumber;}
+ static Module *GetModule(nLoadOut::tModuleType type, UINT8 number);
+
+protected:
+ explicit Module(nLoadOut::tModuleType type, UINT8 number);
+ virtual ~Module();
+
+ nLoadOut::tModuleType m_moduleType; ///< The type of module represented.
+ UINT8 m_moduleNumber; ///< The module index within the module type.
+
+private:
+ static UINT8 ToIndex(nLoadOut::tModuleType type, UINT8 number);
+ static Module* m_modules[kMaxModules];
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/MotorSafety.h b/aos/externals/WPILib/WPILib/MotorSafety.h
new file mode 100644
index 0000000..15481d8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/MotorSafety.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#ifndef _MOTOR_SAFETY_
+#define _MOTOR_SAFETY_
+
+#define DEFAULT_SAFETY_EXPIRATION 0.1
+
+class MotorSafety {
+public:
+ virtual void SetExpiration(float timeout) = 0;
+ virtual float GetExpiration() = 0;
+ virtual bool IsAlive() = 0;
+ virtual void StopMotor() = 0;
+ virtual void SetSafetyEnabled(bool enabled) = 0;
+ virtual bool IsSafetyEnabled() = 0;
+ virtual void GetDescription(char *desc) = 0;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/MotorSafetyHelper.cpp b/aos/externals/WPILib/WPILib/MotorSafetyHelper.cpp
new file mode 100644
index 0000000..eb68566
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/MotorSafetyHelper.cpp
@@ -0,0 +1,155 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "MotorSafetyHelper.h"
+
+#include "DriverStation.h"
+#include "MotorSafety.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+
+#include <stdio.h>
+
+MotorSafetyHelper *MotorSafetyHelper::m_headHelper = NULL;
+Semaphore MotorSafetyHelper::m_listMutex;
+
+/**
+ * The constructor for a MotorSafetyHelper object.
+ * The helper object is constructed for every object that wants to implement the Motor
+ * Safety protocol. The helper object has the code to actually do the timing and call the
+ * motors Stop() method when the timeout expires. The motor object is expected to call the
+ * Feed() method whenever the motors value is updated.
+ * @param safeObject a pointer to the motor object implementing MotorSafety. This is used
+ * to call the Stop() method on the motor.
+ */
+MotorSafetyHelper::MotorSafetyHelper(MotorSafety *safeObject)
+{
+ m_safeObject = safeObject;
+ m_enabled = false;
+ m_expiration = DEFAULT_SAFETY_EXPIRATION;
+ m_stopTime = Timer::GetFPGATimestamp();
+
+ Synchronized sync(m_listMutex);
+ m_nextHelper = m_headHelper;
+ m_headHelper = this;
+}
+
+
+MotorSafetyHelper::~MotorSafetyHelper()
+{
+ Synchronized sync(m_listMutex);
+ if (m_headHelper == this)
+ {
+ m_headHelper = m_nextHelper;
+ }
+ else
+ {
+ MotorSafetyHelper *prev = NULL;
+ MotorSafetyHelper *cur = m_headHelper;
+ while (cur != this && cur != NULL)
+ prev = cur, cur = cur->m_nextHelper;
+ if (cur == this)
+ prev->m_nextHelper = cur->m_nextHelper;
+ }
+}
+
+/*
+ * Feed the motor safety object.
+ * Resets the timer on this object that is used to do the timeouts.
+ */
+void MotorSafetyHelper::Feed()
+{
+ Synchronized sync(m_syncMutex);
+ m_stopTime = Timer::GetFPGATimestamp() + m_expiration;
+}
+
+/*
+ * Set the expiration time for the corresponding motor safety object.
+ * @param expirationTime The timeout value in seconds.
+ */
+void MotorSafetyHelper::SetExpiration(float expirationTime)
+{
+ Synchronized sync(m_syncMutex);
+ m_expiration = expirationTime;
+}
+
+/**
+ * Retrieve the timeout value for the corresponding motor safety object.
+ * @returns the timeout value in seconds.
+ */
+float MotorSafetyHelper::GetExpiration()
+{
+ Synchronized sync(m_syncMutex);
+ return m_expiration;
+}
+
+/**
+ * Determine if the motor is still operating or has timed out.
+ * @returns a true value if the motor is still operating normally and hasn't timed out.
+ */
+bool MotorSafetyHelper::IsAlive()
+{
+ Synchronized sync(m_syncMutex);
+ return !m_enabled || m_stopTime > Timer::GetFPGATimestamp();
+}
+
+/**
+ * Check if this motor has exceeded its timeout.
+ * This method is called periodically to determine if this motor has exceeded its timeout
+ * value. If it has, the stop method is called, and the motor is shut down until its value is
+ * updated again.
+ */
+void MotorSafetyHelper::Check()
+{
+ if (!m_enabled) return;
+ if (DriverStation::GetInstance()->IsDisabled()) return;
+ Synchronized sync(m_syncMutex);
+ if (m_stopTime < Timer::GetFPGATimestamp())
+ {
+ char buf[128];
+ char desc[64];
+ m_safeObject->GetDescription(desc);
+ snprintf(buf, 128, "%s... Output not updated often enough.", desc);
+ wpi_setWPIErrorWithContext(Timeout, buf);
+ m_safeObject->StopMotor();
+ }
+}
+
+/**
+ * Enable/disable motor safety for this device
+ * Turn on and off the motor safety option for this PWM object.
+ * @param enabled True if motor safety is enforced for this object
+ */
+void MotorSafetyHelper::SetSafetyEnabled(bool enabled)
+{
+ Synchronized sync(m_syncMutex);
+ m_enabled = enabled;
+}
+
+/**
+ * Return the state of the motor safety enabled flag
+ * Return if the motor safety is currently enabled for this devicce.
+ * @returns True if motor safety is enforced for this device
+ */
+bool MotorSafetyHelper::IsSafetyEnabled()
+{
+ Synchronized sync(m_syncMutex);
+ return m_enabled;
+}
+
+/**
+ * Check the motors to see if any have timed out.
+ * This static method is called periodically to poll all the motors and stop any that have
+ * timed out.
+ */
+void MotorSafetyHelper::CheckMotors()
+{
+ Synchronized sync(m_listMutex);
+ for (MotorSafetyHelper *msh = m_headHelper; msh != NULL; msh = msh->m_nextHelper)
+ {
+ msh->Check();
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/MotorSafetyHelper.h b/aos/externals/WPILib/WPILib/MotorSafetyHelper.h
new file mode 100644
index 0000000..40ccddc
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/MotorSafetyHelper.h
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __MOTOR_SAFETY_HELPER__
+#define __MOTOR_SAFETY_HELPER__
+
+#include "ErrorBase.h"
+#include "Synchronized.h"
+#include <semLib.h>
+
+class MotorSafety;
+
+class MotorSafetyHelper : public ErrorBase
+{
+public:
+ MotorSafetyHelper(MotorSafety *safeObject);
+ ~MotorSafetyHelper();
+ void Feed();
+ void SetExpiration(float expirationTime);
+ float GetExpiration();
+ bool IsAlive();
+ void Check();
+ void SetSafetyEnabled(bool enabled);
+ bool IsSafetyEnabled();
+ static void CheckMotors();
+private:
+ double m_expiration; // the expiration time for this object
+ bool m_enabled; // true if motor safety is enabled for this motor
+ double m_stopTime; // the FPGA clock value when this motor has expired
+ MotorSafety *m_safeObject; // the object that is using the helper
+ MotorSafetyHelper *m_nextHelper; // next object in the list of MotorSafetyHelpers
+ static MotorSafetyHelper *m_headHelper; // the head of the list of MotorSafetyHelper objects
+ static Semaphore m_listMutex; // protect accesses to the list of helpers
+ Semaphore m_syncMutex; // protect accesses to the state for this object
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkCommunication/AICalibration.h b/aos/externals/WPILib/WPILib/NetworkCommunication/AICalibration.h
new file mode 100644
index 0000000..676e7ea
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkCommunication/AICalibration.h
@@ -0,0 +1,19 @@
+
+#ifndef __AICalibration_h__
+#define __AICalibration_h__
+
+#include <vxWorks.h>
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+ UINT32 FRC_NetworkCommunication_nAICalibration_getLSBWeight(const UINT32 aiSystemIndex, const UINT32 channel, INT32 *status);
+ INT32 FRC_NetworkCommunication_nAICalibration_getOffset(const UINT32 aiSystemIndex, const UINT32 channel, INT32 *status);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // __AICalibration_h__
diff --git a/aos/externals/WPILib/WPILib/NetworkCommunication/FRCComm.h b/aos/externals/WPILib/WPILib/NetworkCommunication/FRCComm.h
new file mode 100644
index 0000000..6a7e3f0
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkCommunication/FRCComm.h
@@ -0,0 +1,154 @@
+/*************************************************************
+ * NOTICE
+ *
+ * These are the only externally exposed functions to the
+ * NetworkCommunication library
+ *
+ * This is an implementation of FRC Spec for Comm Protocol
+ * Revision 4.5, June 30, 2008
+ *
+ * Copyright (c) National Instruments 2008. All Rights Reserved.
+ *
+ *************************************************************/
+
+#ifndef __FRC_COMM_H__
+#define __FRC_COMM_H__
+
+#include <vxWorks.h>
+
+// Commandeer some bytes at the end for advanced I/O feedback.
+#define IO_CONFIG_DATA_SIZE 32
+#define SYS_STATUS_DATA_SIZE 44
+#define USER_STATUS_DATA_SIZE (984 - IO_CONFIG_DATA_SIZE - SYS_STATUS_DATA_SIZE)
+#define USER_DS_LCD_DATA_SIZE 128
+
+struct FRCCommonControlData{
+ UINT16 packetIndex;
+ union {
+ UINT8 control;
+ struct {
+ UINT8 reset : 1;
+ UINT8 notEStop : 1;
+ UINT8 enabled : 1;
+ UINT8 autonomous : 1;
+ UINT8 fmsAttached:1;
+ UINT8 resync : 1;
+ UINT8 cRIOChkSum :1;
+ UINT8 fpgaChkSum :1;
+ };
+ };
+ UINT8 dsDigitalIn;
+ UINT16 teamID;
+
+ char dsID_Alliance;
+ char dsID_Position;
+
+ union {
+ INT8 stick0Axes[6];
+ struct {
+ INT8 stick0Axis1;
+ INT8 stick0Axis2;
+ INT8 stick0Axis3;
+ INT8 stick0Axis4;
+ INT8 stick0Axis5;
+ INT8 stick0Axis6;
+ };
+ };
+ UINT16 stick0Buttons; // Left-most 4 bits are unused
+
+ union {
+ INT8 stick1Axes[6];
+ struct {
+ INT8 stick1Axis1;
+ INT8 stick1Axis2;
+ INT8 stick1Axis3;
+ INT8 stick1Axis4;
+ INT8 stick1Axis5;
+ INT8 stick1Axis6;
+ };
+ };
+ UINT16 stick1Buttons; // Left-most 4 bits are unused
+
+ union {
+ INT8 stick2Axes[6];
+ struct {
+ INT8 stick2Axis1;
+ INT8 stick2Axis2;
+ INT8 stick2Axis3;
+ INT8 stick2Axis4;
+ INT8 stick2Axis5;
+ INT8 stick2Axis6;
+ };
+ };
+ UINT16 stick2Buttons; // Left-most 4 bits are unused
+
+ union {
+ INT8 stick3Axes[6];
+ struct {
+ INT8 stick3Axis1;
+ INT8 stick3Axis2;
+ INT8 stick3Axis3;
+ INT8 stick3Axis4;
+ INT8 stick3Axis5;
+ INT8 stick3Axis6;
+ };
+ };
+ UINT16 stick3Buttons; // Left-most 4 bits are unused
+
+ //Analog inputs are 10 bit right-justified
+ UINT16 analog1;
+ UINT16 analog2;
+ UINT16 analog3;
+ UINT16 analog4;
+
+ UINT64 cRIOChecksum;
+ UINT32 FPGAChecksum0;
+ UINT32 FPGAChecksum1;
+ UINT32 FPGAChecksum2;
+ UINT32 FPGAChecksum3;
+
+ char versionData[8];
+};
+
+#define kFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Input 17
+#define kFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Output 18
+#define kFRC_NetworkCommunication_DynamicType_Kinect_Header 19
+#define kFRC_NetworkCommunication_DynamicType_Kinect_Extra1 20
+#define kFRC_NetworkCommunication_DynamicType_Kinect_Vertices1 21
+#define kFRC_NetworkCommunication_DynamicType_Kinect_Extra2 22
+#define kFRC_NetworkCommunication_DynamicType_Kinect_Vertices2 23
+#define kFRC_NetworkCommunication_DynamicType_Kinect_Joystick 24
+#define kFRC_NetworkCommunication_DynamicType_Kinect_Custom 25
+
+extern "C" {
+ void getFPGAHardwareVersion(UINT16 *fpgaVersion, UINT32 *fpgaRevision);
+ int getCommonControlData(FRCCommonControlData *data, int wait_ms);
+ int getRecentCommonControlData(FRCCommonControlData *commonData, int wait_ms);
+ int getRecentStatusData(UINT8 *batteryInt, UINT8 *batteryDec, UINT8 *dsDigitalOut, int wait_ms);
+ int getDynamicControlData(UINT8 type, char *dynamicData, INT32 maxLength, int wait_ms);
+ int setStatusData(float battery, UINT8 dsDigitalOut, UINT8 updateNumber,
+ const char *userDataHigh, int userDataHighLength,
+ const char *userDataLow, int userDataLowLength, int wait_ms);
+ int setStatusDataFloatAsInt(int battery, UINT8 dsDigitalOut, UINT8 updateNumber,
+ const char *userDataHigh, int userDataHighLength,
+ const char *userDataLow, int userDataLowLength, int wait_ms);
+ int setErrorData(const char *errors, int errorsLength, int wait_ms);
+ int setUserDsLcdData(const char *userDsLcdData, int userDsLcdDataLength, int wait_ms);
+ int overrideIOConfig(const char *ioConfig, int wait_ms);
+
+ void setNewDataSem(SEM_ID);
+ void setResyncSem(SEM_ID);
+ void signalResyncActionDone(void);
+
+ // this UINT32 is really a LVRefNum
+ void setNewDataOccurRef(UINT32 refnum);
+ void setResyncOccurRef(UINT32 refnum);
+
+ void FRC_NetworkCommunication_getVersionString(char *version);
+ void FRC_NetworkCommunication_observeUserProgramStarting(void);
+ void FRC_NetworkCommunication_observeUserProgramDisabled(void);
+ void FRC_NetworkCommunication_observeUserProgramAutonomous(void);
+ void FRC_NetworkCommunication_observeUserProgramTeleop(void);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkCommunication/LoadOut.h b/aos/externals/WPILib/WPILib/NetworkCommunication/LoadOut.h
new file mode 100644
index 0000000..7ebe105
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkCommunication/LoadOut.h
@@ -0,0 +1,39 @@
+
+#ifndef __LoadOut_h__
+#define __LoadOut_h__
+
+#define kMaxModuleNumber 2
+namespace nLoadOut
+{
+ typedef enum {
+ kModuleType_Unknown = 0x00,
+ kModuleType_Analog = 0x01,
+ kModuleType_Digital = 0x02,
+ kModuleType_Solenoid = 0x03,
+ } tModuleType;
+ bool getModulePresence(tModuleType moduleType, UINT8 moduleNumber);
+ typedef enum {
+ kTargetClass_Unknown = 0x00,
+ kTargetClass_FRC1 = 0x10,
+ kTargetClass_FRC2 = 0x20,
+ kTargetClass_FRC2_Analog = kTargetClass_FRC2 | kModuleType_Analog,
+ kTargetClass_FRC2_Digital = kTargetClass_FRC2 | kModuleType_Digital,
+ kTargetClass_FRC2_Solenoid = kTargetClass_FRC2 | kModuleType_Solenoid,
+ kTargetClass_FamilyMask = 0xF0,
+ kTargetClass_ModuleMask = 0x0F,
+ } tTargetClass;
+ tTargetClass getTargetClass();
+}
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+ UINT32 FRC_NetworkCommunication_nLoadOut_getModulePresence(UINT32 moduleType, UINT8 moduleNumber);
+ UINT32 FRC_NetworkCommunication_nLoadOut_getTargetClass();
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // __LoadOut_h__
diff --git a/aos/externals/WPILib/WPILib/NetworkCommunication/Makefile b/aos/externals/WPILib/WPILib/NetworkCommunication/Makefile
new file mode 100644
index 0000000..bc19164
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkCommunication/Makefile
@@ -0,0 +1,2184 @@
+# Wind River Workbench generated Makefile.
+# Do not edit!!!
+#
+# The file ".wrmakefile" is the template used by the Wind River Workbench to
+# generate the makefiles of this project. Add user-specific build targets and
+# make rules only(!) in this project's ".wrmakefile" file. These will then be
+# automatically dumped into the makefiles.
+
+WIND_HOME := $(subst \,/,$(WIND_HOME))
+WIND_BASE := $(subst \,/,$(WIND_BASE))
+WIND_USR := $(subst \,/,$(WIND_USR))
+
+all : pre_build main_all post_build
+
+_clean ::
+ @echo "make: removing targets and objects of `pwd`"
+
+TRACE=0
+TRACEON=$(TRACE:0=@)
+TRACE_FLAG=$(TRACEON:1=)
+
+MAKEFILE := Makefile
+
+BUILD_SPEC = PPC603gnu
+DEBUG_MODE = 1
+SRC_DIR := .
+BUILD_ROOT_DIR :=
+PRJ_ROOT_DIR := C:/windriver/workspace/WPILib
+WS_ROOT_DIR := C:/windriver/workspace
+
+ALL_BUILD_SPECS := PPC32diab PPC32gnu PPC32sfdiab PPC32sfgnu \
+ PPC403diab PPC403gnu PPC405diab PPC405gnu \
+ PPC405sfdiab PPC405sfgnu PPC440diab PPC440gnu \
+ PPC440sfdiab PPC440sfgnu PPC603diab PPC603gnu \
+ PPC604diab PPC604gnu PPC85XXdiab PPC85XXgnu \
+ PPC85XXsfdiab PPC85XXsfgnu PPC860sfdiab PPC860sfgnu \
+ SIMLINUXdiab SIMLINUXgnu SIMNTdiab SIMNTgnu \
+ SIMSPARCSOLARISdiab SIMSPARCSOLARISgnu
+ENABLED_BUILD_SPECS := PPC603gnu
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32diab_DEBUG
+else
+OBJ_DIR := PPC32diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32gnu_DEBUG
+else
+OBJ_DIR := PPC32gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfdiab_DEBUG
+else
+OBJ_DIR := PPC32sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfgnu_DEBUG
+else
+OBJ_DIR := PPC32sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403diab_DEBUG
+else
+OBJ_DIR := PPC403diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403gnu_DEBUG
+else
+OBJ_DIR := PPC403gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405diab_DEBUG
+else
+OBJ_DIR := PPC405diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405gnu_DEBUG
+else
+OBJ_DIR := PPC405gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfdiab_DEBUG
+else
+OBJ_DIR := PPC405sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfgnu_DEBUG
+else
+OBJ_DIR := PPC405sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440diab_DEBUG
+else
+OBJ_DIR := PPC440diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440gnu_DEBUG
+else
+OBJ_DIR := PPC440gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfdiab_DEBUG
+else
+OBJ_DIR := PPC440sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfgnu_DEBUG
+else
+OBJ_DIR := PPC440sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603diab_DEBUG
+else
+OBJ_DIR := PPC603diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603gnu_DEBUG
+else
+OBJ_DIR := PPC603gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604diab_DEBUG
+else
+OBJ_DIR := PPC604diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604gnu_DEBUG
+else
+OBJ_DIR := PPC604gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXdiab_DEBUG
+else
+OBJ_DIR := PPC85XXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXgnu_DEBUG
+else
+OBJ_DIR := PPC85XXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfdiab_DEBUG
+else
+OBJ_DIR := PPC85XXsfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfgnu_DEBUG
+else
+OBJ_DIR := PPC85XXsfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfdiab_DEBUG
+else
+OBJ_DIR := PPC860sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfgnu_DEBUG
+else
+OBJ_DIR := PPC860sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXdiab_DEBUG
+else
+OBJ_DIR := SIMLINUXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXgnu_DEBUG
+else
+OBJ_DIR := SIMLINUXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTdiab_DEBUG
+else
+OBJ_DIR := SIMNTdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTgnu_DEBUG
+else
+OBJ_DIR := SIMNTgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISdiab_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISgnu_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISgnu
+endif
+endif
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+
+PROJECT_TYPE = DKM
+DEFINES =
+EXPAND_DBG = 0
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFH:vxworks63 -Xstmw-slow -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mhard-float -mstrict-align -mno-implicit-fp -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -msoft-float -mstrict-align
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC403FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=403 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC603FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=603 -mstrict-align -mno-implicit-fp -mlongcall
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I.. -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC604FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=604 -mstrict-align -mno-implicit-fp
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC860FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=860 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tSPARCFH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC =
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+
+
+
+
+
+-include $(PRJ_ROOT_DIR)/*.makefile
+
+-include *.makefile
+
+main_all : external_build $(PROJECT_TARGETS)
+ @echo "make: built targets of `pwd`"
+
+# entry point for extending the build
+external_build ::
+ @echo ""
+
+# main entry point for pre processing prior to the build
+pre_build :: $(PRE_BUILD_STEP) generate_sources
+ @echo ""
+
+# entry point for generating sources prior to the build
+generate_sources ::
+ @echo ""
+
+# main entry point for post processing after the build
+post_build :: $(POST_BUILD_STEP) deploy_output
+ @echo ""
+
+# entry point for deploying output after the build
+deploy_output ::
+ @echo ""
+
+clean :: external_clean $(CLEAN_STEP) _clean
+
+# entry point for extending the build clean
+external_clean ::
+ @echo ""
diff --git a/aos/externals/WPILib/WPILib/NetworkCommunication/UsageReporting.h b/aos/externals/WPILib/WPILib/NetworkCommunication/UsageReporting.h
new file mode 100644
index 0000000..daf0ac4
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkCommunication/UsageReporting.h
@@ -0,0 +1,124 @@
+
+#ifndef __UsageReporting_h__
+#define __UsageReporting_h__
+
+#include <vxWorks.h>
+
+#define kUsageReporting_version 1
+
+namespace nUsageReporting
+{
+ typedef enum
+ {
+ kResourceType_Controller,
+ kResourceType_Module,
+ kResourceType_Language,
+ kResourceType_CANPlugin,
+ kResourceType_Accelerometer,
+ kResourceType_ADXL345,
+ kResourceType_AnalogChannel,
+ kResourceType_AnalogTrigger,
+ kResourceType_AnalogTriggerOutput,
+ kResourceType_CANJaguar,
+ kResourceType_Compressor,
+ kResourceType_Counter,
+ kResourceType_Dashboard,
+ kResourceType_DigitalInput,
+ kResourceType_DigitalOutput,
+ kResourceType_DriverStationCIO,
+ kResourceType_DriverStationEIO,
+ kResourceType_DriverStationLCD,
+ kResourceType_Encoder,
+ kResourceType_GearTooth,
+ kResourceType_Gyro,
+ kResourceType_I2C,
+ kResourceType_Framework,
+ kResourceType_Jaguar,
+ kResourceType_Joystick,
+ kResourceType_Kinect,
+ kResourceType_KinectStick,
+ kResourceType_PIDController,
+ kResourceType_Preferences,
+ kResourceType_PWM,
+ kResourceType_Relay,
+ kResourceType_RobotDrive,
+ kResourceType_SerialPort,
+ kResourceType_Servo,
+ kResourceType_Solenoid,
+ kResourceType_SPI,
+ kResourceType_Task,
+ kResourceType_Ultrasonic,
+ kResourceType_Victor,
+ kResourceType_Button,
+ kResourceType_Command,
+ kResourceType_AxisCamera,
+ kResourceType_PCVideoServer,
+ kResourceType_SmartDashboard,
+ } tResourceType;
+
+ typedef enum
+ {
+ kLanguage_LabVIEW = 1,
+ kLanguage_CPlusPlus = 2,
+ kLanguage_Java = 3,
+ kLanguage_Python = 4,
+
+ kCANPlugin_BlackJagBridge = 1,
+ kCANPlugin_2CAN = 2,
+
+ kFramework_Iterative = 1,
+ kFramework_Simple = 2,
+
+ kRobotDrive_ArcadeStandard = 1,
+ kRobotDrive_ArcadeButtonSpin = 2,
+ kRobotDrive_ArcadeRatioCurve = 3,
+ kRobotDrive_Tank = 4,
+ kRobotDrive_MecanumPolar = 5,
+ kRobotDrive_MecanumCartesian = 6,
+
+ kDriverStationCIO_Analog = 1,
+ kDriverStationCIO_DigitalIn = 2,
+ kDriverStationCIO_DigitalOut = 3,
+
+ kDriverStationEIO_Acceleration = 1,
+ kDriverStationEIO_AnalogIn = 2,
+ kDriverStationEIO_AnalogOut = 3,
+ kDriverStationEIO_Button = 4,
+ kDriverStationEIO_LED = 5,
+ kDriverStationEIO_DigitalIn = 6,
+ kDriverStationEIO_DigitalOut = 7,
+ kDriverStationEIO_FixedDigitalOut = 8,
+ kDriverStationEIO_PWM = 9,
+ kDriverStationEIO_Encoder = 10,
+ kDriverStationEIO_TouchSlider = 11,
+
+ kADXL345_SPI = 1,
+ kADXL345_I2C = 1,
+
+ kCommand_Scheduler = 1,
+
+ kSmartDashboard_Instance = 1,
+ } tInstances;
+
+ /**
+ * Report the usage of a resource of interest.
+ *
+ * @param resource one of the values in the tResourceType above (max value 51).
+ * @param instanceNumber an index that identifies the resource instance.
+ * @param context an optional additional context number for some cases (such as module number). Set to 0 to omit.
+ * @param feature a string to be included describing features in use on a specific resource. Setting the same resource more than once allows you to change the feature string.
+ */
+ UINT32 report(tResourceType resource, UINT8 instanceNumber, UINT8 context = 0, const char *feature = NULL);
+}
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+ UINT32 FRC_NetworkCommunication_nUsageReporting_report(UINT8 resource, UINT8 instanceNumber, UINT8 context, const char *feature);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // __UsageReporting_h__
diff --git a/aos/externals/WPILib/WPILib/NetworkCommunication/symModuleLink.h b/aos/externals/WPILib/WPILib/NetworkCommunication/symModuleLink.h
new file mode 100644
index 0000000..dac419d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkCommunication/symModuleLink.h
@@ -0,0 +1,21 @@
+#ifndef __SYM_MODULE_LINK_H__
+#define __SYM_MODULE_LINK_H__
+
+#include <vxWorks.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+extern STATUS moduleNameFindBySymbolName
+ (
+ const char * symbol, /* symbol name to look for */
+ char * module /* where to return module name */
+ );
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/BooleanEntry.cpp b/aos/externals/WPILib/WPILib/NetworkTables/BooleanEntry.cpp
new file mode 100644
index 0000000..7273bd7
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/BooleanEntry.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/BooleanEntry.h"
+#include "NetworkTables/Buffer.h"
+
+namespace NetworkTables
+{
+
+BooleanEntry::BooleanEntry(bool value) :
+ m_value(value)
+{
+}
+
+NetworkTables_Types BooleanEntry::GetType()
+{
+ return kNetworkTables_Types_BOOLEAN;
+}
+
+void BooleanEntry::Encode(Buffer *buffer)
+{
+ Entry::Encode(buffer);
+ buffer->WriteByte(m_value ? kNetworkTables_BOOLEAN_TRUE
+ : kNetworkTables_BOOLEAN_FALSE);
+}
+
+bool BooleanEntry::GetBoolean()
+{
+ return m_value;
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/BooleanEntry.h b/aos/externals/WPILib/WPILib/NetworkTables/BooleanEntry.h
new file mode 100644
index 0000000..4481b57
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/BooleanEntry.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __BOOLEAN_ENTRY_H__
+#define __BOOLEAN_ENTRY_H__
+
+#include "NetworkTables/Entry.h"
+#include "NetworkTables/InterfaceConstants.h"
+#include <vxWorks.h>
+
+class NetworkTable;
+
+namespace NetworkTables
+{
+
+class Buffer;
+
+class BooleanEntry : public Entry {
+public:
+ BooleanEntry(bool value);
+ virtual NetworkTables_Types GetType();
+ virtual void Encode(Buffer *buffer);
+ virtual bool GetBoolean();
+
+private:
+ bool m_value;
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Buffer.cpp b/aos/externals/WPILib/WPILib/NetworkTables/Buffer.cpp
new file mode 100644
index 0000000..29d4002
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Buffer.cpp
@@ -0,0 +1,157 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/Buffer.h"
+#include "NetworkTables/InterfaceConstants.h"
+#include "WPIErrors.h"
+#include <sockLib.h>
+#include <string.h>
+
+namespace NetworkTables
+{
+
+Buffer::Buffer(UINT32 capacity) :
+ m_buffer (NULL),
+ m_size (0),
+ m_capacity (capacity)
+{
+ m_buffer = new UINT8[capacity];
+}
+
+Buffer::~Buffer()
+{
+ delete [] m_buffer;
+}
+
+void Buffer::WriteString(UINT32 length, const char *entry)
+{
+ if (length >= kNetworkTables_BEGIN_STRING)
+ {
+ WriteByte(kNetworkTables_BEGIN_STRING);
+ WriteBytes(length, (UINT8*)entry);
+ WriteByte(kNetworkTables_END_STRING);
+ }
+ else
+ {
+ WriteByte(length);
+ WriteBytes(length, (UINT8*)entry);
+ }
+}
+
+void Buffer::WriteString(const char *entry)
+{
+ WriteString(strlen(entry), entry);
+}
+
+void Buffer::WriteString(std::string entry)
+{
+ WriteString(entry.length(), entry.c_str());
+}
+
+void Buffer::WriteDouble(double entry)
+{
+ WriteBytes(sizeof(entry), (UINT8*) &entry);
+}
+
+void Buffer::WriteInt(UINT32 entry)
+{
+ WriteBytes(sizeof(entry), (UINT8*) &entry);
+}
+
+void Buffer::WriteId(UINT32 id)
+{
+ WriteVariableSize(kNetworkTables_ID, id);
+}
+
+void Buffer::WriteTableId(UINT32 id)
+{
+ WriteVariableSize(kNetworkTables_TABLE_ID, id);
+}
+
+void Buffer::WriteBytes(UINT32 length, const UINT8 *entries)
+{
+ UINT32 i;
+ for (i = 0; i < length; i++)
+ {
+ WriteByte(entries[i]);
+ }
+}
+
+void Buffer::WriteByte(UINT8 entry)
+{
+ if (m_size >= m_capacity)
+ {
+ wpi_setWPIError(NetworkTablesBufferFull);
+ return;
+ }
+ m_buffer[m_size++] = entry;
+}
+
+void Buffer::Flush(int socket)
+{
+#ifdef DEBUG
+ if (m_size != 1 || m_buffer[0] != kNetworkTables_PING)
+ {
+ unsigned i;
+ char buf[128];
+ char *pbuf = buf;
+ pbuf = pbuf + snprintf(pbuf, 128 - (pbuf - buf), "\nO:");
+ for (i=0; i<m_size; i++)
+ {
+ pbuf = pbuf + snprintf(pbuf, 128 - (pbuf - buf), "%02X", m_buffer[i]);
+ }
+ snprintf(pbuf, 128 - (pbuf - buf), "\n");
+ printf(buf);
+ }
+#endif
+ write(socket, (char *)m_buffer, m_size);
+ Clear();
+}
+
+void Buffer::Clear()
+{
+ m_size = 0;
+}
+
+void Buffer::WriteVariableSize(UINT32 tag, UINT32 id)
+{
+ if (id < tag - 4)
+ {
+ WriteByte(tag | id);
+ }
+ else
+ {
+ int fullTag = (tag | (tag - 1)) ^ 3;
+ if (id < (1 << 8))
+ {
+ WriteByte(fullTag);
+ WriteByte(id);
+ }
+ else if (id < (1 << 16))
+ {
+ WriteByte(fullTag | 1);
+ WriteByte(id >> 8);
+ WriteByte(id);
+ }
+ else if (id < (1 << 24))
+ {
+ WriteByte(fullTag | 2);
+ WriteByte(id >> 16);
+ WriteByte(id >> 8);
+ WriteByte(id);
+ }
+ else
+ {
+ WriteByte(fullTag | 3);
+ WriteByte(id >> 24);
+ WriteByte(id >> 16);
+ WriteByte(id >> 8);
+ WriteByte(id);
+ }
+ }
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Buffer.h b/aos/externals/WPILib/WPILib/NetworkTables/Buffer.h
new file mode 100644
index 0000000..164da96
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Buffer.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __BUFFER_H__
+#define __BUFFER_H__
+
+#include "ErrorBase.h"
+#include <vxWorks.h>
+#include <string>
+
+namespace NetworkTables
+{
+
+class Buffer : public ErrorBase
+{
+public:
+ Buffer(UINT32 capacity);
+ ~Buffer();
+ void WriteString(UINT32 length, const char *entry);
+ void WriteString(const char *entry);
+ void WriteString(std::string entry);
+ void WriteDouble(double entry);
+ void WriteInt(UINT32 entry);
+ void WriteId(UINT32 id);
+ void WriteTableId(UINT32 id);
+ void WriteBytes(UINT32 length, const UINT8 *entries);
+ void WriteByte(UINT8 entry);
+ void Flush(int socket);
+ void Clear();
+
+private:
+ void WriteVariableSize(UINT32 tag, UINT32 id);
+
+ UINT8 *m_buffer;
+ UINT32 m_size;
+ UINT32 m_capacity;
+};
+
+} // namespace
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Confirmation.cpp b/aos/externals/WPILib/WPILib/NetworkTables/Confirmation.cpp
new file mode 100644
index 0000000..129c889
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Confirmation.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/Confirmation.h"
+#include "NetworkTables/Buffer.h"
+#include "NetworkTables/InterfaceConstants.h"
+
+namespace NetworkTables
+{
+
+Confirmation::Confirmation(int count) :
+ m_count(count)
+{
+}
+
+void Confirmation::Encode(Buffer *buffer)
+{
+ for (int i = m_count; i > 0; i -= kNetworkTables_CONFIRMATION - 1)
+ {
+ buffer->WriteByte(kNetworkTables_CONFIRMATION | std::min(kNetworkTables_CONFIRMATION - 1, i));
+ }
+}
+
+// Currently unused
+Confirmation *Confirmation::Combine(Confirmation *a, Confirmation *b)
+{
+ a->m_count = a->m_count + b->m_count;
+ delete b;
+ return a;
+}
+
+}
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Confirmation.h b/aos/externals/WPILib/WPILib/NetworkTables/Confirmation.h
new file mode 100644
index 0000000..6ecc7e7
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Confirmation.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __CONFIRMATION_H__
+#define __CONFIRMATION_H__
+
+#include "NetworkTables/Data.h"
+
+namespace NetworkTables
+{
+
+class Buffer;
+
+class Confirmation : public Data
+{
+public:
+ Confirmation(int count);
+ virtual void Encode(Buffer *buffer);
+private:
+ static Confirmation *Combine(Confirmation *a, Confirmation *b);
+
+ int m_count;
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Connection.cpp b/aos/externals/WPILib/WPILib/NetworkTables/Connection.cpp
new file mode 100644
index 0000000..7abc3df
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Connection.cpp
@@ -0,0 +1,591 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/Connection.h"
+
+#include "NetworkTables/Buffer.h"
+#include "NetworkTables/Confirmation.h"
+#include "NetworkTables/ConnectionManager.h"
+#include "NetworkTables/Data.h"
+#include "NetworkTables/Denial.h"
+#include "NetworkTables/Entry.h"
+#include "NetworkTables/InterfaceConstants.h"
+#include "NetworkTables/Key.h"
+#include "NetworkTables/NetworkQueue.h"
+#include "NetworkTables/NetworkTable.h"
+#include "NetworkTables/OldData.h"
+#include "NetworkTables/Reader.h"
+#include "NetworkTables/TableAssignment.h"
+#include "NetworkTables/TableEntry.h"
+#include "NetworkTables/TransactionEnd.h"
+#include "NetworkTables/TransactionStart.h"
+#include "Synchronized.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+#include <inetLib.h>
+#include <semLib.h>
+#include <sockLib.h>
+#include <string>
+#include <usrLib.h>
+
+namespace NetworkTables
+{
+
+const UINT32 Connection::kWriteDelay;
+const UINT32 Connection::kTimeout;
+
+Connection::Connection(int socket) :
+ m_socket(socket),
+ m_dataLock(NULL),
+ m_dataAvailable(NULL),
+ m_watchdogLock(NULL),
+ m_watchdogFood(NULL),
+ m_queue(NULL),
+ m_transaction(NULL),
+ m_connected(true),
+ m_inTransaction(false),
+ m_denyTransaction(false),
+ m_watchdogActive(false),
+ m_watchdogFed(false),
+ m_readTask("NetworkTablesReadTask", (FUNCPTR)Connection::InitReadTask),
+ m_writeTask("NetworkTablesWriteTask", (FUNCPTR)Connection::InitWriteTask),
+ m_watchdogTask("NetworkTablesWatchdogTask", (FUNCPTR)Connection::InitWatchdogTask),
+ m_transactionStart(NULL),
+ m_transactionEnd(NULL)
+{
+ m_dataLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+ m_dataAvailable = semBCreate (SEM_Q_PRIORITY, SEM_EMPTY);
+ m_watchdogLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+ m_watchdogFood = semBCreate (SEM_Q_PRIORITY, SEM_EMPTY);
+ m_queue = new NetworkQueue();
+ m_transaction = new NetworkQueue();
+ m_transactionStart = new TransactionStart();
+ m_transactionEnd = new TransactionEnd();
+}
+
+Connection::~Connection()
+{
+ delete m_transactionEnd;
+ delete m_transactionStart;
+ delete m_transaction;
+ delete m_queue;
+ semDelete(m_watchdogFood);
+ semTake(m_watchdogLock, WAIT_FOREVER);
+ semDelete(m_watchdogLock);
+ semDelete(m_dataAvailable);
+ semTake(m_dataLock, WAIT_FOREVER);
+ semDelete(m_dataLock);
+}
+
+void Connection::OfferTransaction(NetworkQueue *transaction)
+{
+ Synchronized sync(m_dataLock);
+ NetworkQueue::DataQueue_t::const_iterator it = transaction->GetQueueHead();
+ for (; !transaction->IsQueueEnd(it); it++)
+ {
+ Data *data = it->first;
+ if (data->IsEntry() && ((Entry *)data)->GetType() == kNetworkTables_TABLE)
+ {
+ NetworkTable *table = ((TableEntry *)data)->GetTable();
+ table->AddConnection(this);
+ }
+ }
+ m_queue->Offer(m_transactionStart);
+ it = transaction->GetQueueHead();
+ for (; !transaction->IsQueueEnd(it); it++)
+ {
+ // We are always offering something from a transaction that has yet to be used locally...
+ // They will be cleaned up if necessary in the local use.
+ m_queue->Offer(it->first);
+ }
+ m_queue->Offer(m_transactionEnd);
+ semGive(m_dataAvailable);
+}
+
+void Connection::Offer(Data *data)
+{
+ if (data != NULL)
+ {
+ Synchronized sync(m_dataLock);
+ if (data->IsEntry() && ((Entry *)data)->GetType() == kNetworkTables_TABLE)
+ {
+ NetworkTable *table = ((TableEntry *)data)->GetTable();
+ table->AddConnection(this);
+ }
+ m_queue->Offer(data);
+ semGive(m_dataAvailable);
+ }
+}
+
+void Connection::Offer(std::auto_ptr<Data> autoData)
+{
+ Synchronized sync(m_dataLock);
+ if (autoData->IsEntry() && ((Entry *)autoData.get())->GetType() == kNetworkTables_TABLE)
+ {
+ NetworkTable *table = ((TableEntry *)autoData.get())->GetTable();
+ table->AddConnection(this);
+ }
+ m_queue->Offer(autoData);
+ semGive(m_dataAvailable);
+}
+
+void Connection::Start()
+{
+ m_watchdogTask.Start((UINT32)this);
+ m_readTask.Start((UINT32)this);
+ m_writeTask.Start((UINT32)this);
+}
+
+void Connection::ReadTaskRun()
+{
+ Reader input(this, m_socket);
+ int value;
+
+ value = input.Read();
+ while (m_connected)
+ {
+ WatchdogFeed();
+ WatchdogActivate();
+
+ if (value >= kNetworkTables_ID || value == kNetworkTables_OLD_DATA)
+ {
+ bool oldData = value == kNetworkTables_OLD_DATA;
+ UINT32 id = input.ReadId(!oldData);
+ if (!m_connected)
+ break;
+ Key *key = Key::GetKey(m_fieldMap[id]);
+#ifdef DEBUG
+ char pbuf[64];
+ snprintf(pbuf, 64, "Update field \"%s\" value remote=%d local=%d\n", key->GetName().c_str(), id, m_fieldMap[id]);
+ printf(pbuf);
+#endif
+
+ if (key == NULL)
+ {
+ wpi_setWPIErrorWithContext(NetworkTablesCorrupt, "Unexpected ID");
+ Close();
+ return;
+ }
+
+ value = input.Read();
+ if (!m_connected)
+ break;
+
+ if (ConnectionManager::GetInstance()->IsServer() && ConfirmationsContainsKey(key))
+ {
+ if (m_inTransaction)
+ m_denyTransaction = true;
+ else
+ Offer(std::auto_ptr<Data>(new Denial(1)));
+ if (value >= kNetworkTables_TABLE_ID)
+ input.ReadTableId(true);
+ else
+ input.ReadEntry(true);
+ }
+ else if (value >= kNetworkTables_TABLE_ID)
+ {
+ UINT32 tableId = input.ReadTableId(true);
+ if (!m_connected)
+ break;
+ if (oldData && key->HasEntry())
+ {
+ Offer(std::auto_ptr<Data>(new Denial(1)));
+ }
+ else
+ {
+ NetworkTable *table = GetTable(false, tableId);
+ Entry *tableEntry = new TableEntry(table);
+ tableEntry->SetSource(this);
+ tableEntry->SetKey(key);
+ if (m_inTransaction)
+ {
+ m_transaction->Offer(std::auto_ptr<Data>(tableEntry));
+ }
+ else
+ {
+ key->GetTable()->Got(false, key, std::auto_ptr<Entry>(tableEntry));
+ Offer(std::auto_ptr<Data>(new Confirmation(1)));
+ }
+ }
+ }
+ else
+ {
+ std::auto_ptr<Entry> entry = input.ReadEntry(true);
+ if (!m_connected)
+ break;
+
+ if (entry.get() == NULL)
+ {
+ wpi_setWPIErrorWithContext(NetworkTablesCorrupt, "Unable to parse entry");
+ Close();
+ return;
+ }
+ else if (oldData && key->HasEntry())
+ {
+ Offer(std::auto_ptr<Data>(new Denial(1)));
+ }
+ else
+ {
+ entry->SetSource(this);
+ entry->SetKey(key);
+ if (m_inTransaction)
+ {
+ m_transaction->Offer(std::auto_ptr<Data>(entry.release()));
+ }
+ else
+ {
+ key->GetTable()->Got(false, key, entry);
+ Offer(std::auto_ptr<Data>(new Confirmation(1)));
+ }
+ }
+ }
+ }
+ else if (value >= kNetworkTables_CONFIRMATION)
+ {
+ int count = input.ReadConfirmations(true);
+ if (!m_connected)
+ break;
+ while (count-- > 0)
+ {
+ if (m_confirmations.empty())
+ {
+ wpi_setWPIErrorWithContext(NetworkTablesCorrupt, "Too many confirmations");
+ Close();
+ return;
+ }
+ Entry *entry = m_confirmations.front();
+ m_confirmations.pop_front();
+ // TransactionStart
+ if (entry == NULL)
+ {
+ if (ConnectionManager::GetInstance()->IsServer())
+ {
+ while (!m_confirmations.empty() && m_confirmations.front() != NULL)
+ m_confirmations.pop_front();
+ }
+ else
+ {
+ while (!m_confirmations.empty() && m_confirmations.front() != NULL)
+ {
+ m_transaction->Offer(m_confirmations.front());
+ m_confirmations.pop_front();
+ }
+
+ if (!m_transaction->IsEmpty())
+ ((Entry *)m_transaction->Peek())->GetKey()->GetTable()->ProcessTransaction(true, m_transaction);
+ }
+ }
+ else if (!ConnectionManager::GetInstance()->IsServer())
+ {
+ entry->GetKey()->GetTable()->Got(true, entry->GetKey(), std::auto_ptr<Entry>(entry));
+ }
+ }
+ }
+ else if (value >= kNetworkTables_DENIAL)
+ {
+ if (ConnectionManager::GetInstance()->IsServer())
+ {
+ wpi_setWPIErrorWithContext(NetworkTablesCorrupt, "Server can not be denied");
+ Close();
+ return;
+ }
+ int count = input.ReadDenials(m_connected);
+ if (!m_connected)
+ break;
+ while (count-- > 0)
+ {
+ if (m_confirmations.empty())
+ {
+ wpi_setWPIErrorWithContext(NetworkTablesCorrupt, "Excess denial");
+ Close();
+ return;
+ }
+ else if (m_confirmations.front() == NULL)
+ {
+ m_confirmations.pop_front();
+ // Skip the transaction
+ while (!m_confirmations.empty() && m_confirmations.front() != NULL)
+ {
+ delete m_confirmations.front();
+ m_confirmations.pop_front();
+ }
+ }
+ else
+ {
+ delete m_confirmations.front();
+ m_confirmations.pop_front();
+ }
+ }
+ }
+ else if (value == kNetworkTables_TABLE_REQUEST)
+ {
+ if (!ConnectionManager::GetInstance()->IsServer())
+ {
+ wpi_setWPIErrorWithContext(NetworkTablesCorrupt, "Server requesting table");
+ Close();
+ return;
+ }
+ std::string name = input.ReadString();
+ if (!m_connected)
+ break;
+ UINT32 id = input.ReadTableId(false);
+ if (!m_connected)
+ break;
+#ifdef DEBUG
+ char pbuf[128];
+ snprintf(pbuf, 128, "Request table: %s (%d)\n", name.c_str(), id);
+ printf(pbuf);
+#endif
+
+ NetworkTable *table = NetworkTable::GetTable(name.c_str());
+
+ {
+ Synchronized sync(m_dataLock);
+ Offer(std::auto_ptr<Data>(new TableAssignment(table, id)));
+ table->AddConnection(this);
+ }
+
+ m_tableMap.insert(IDMap_t::value_type(id, table->GetId()));
+ }
+ else if (value == kNetworkTables_TABLE_ASSIGNMENT)
+ {
+ UINT32 localTableId = input.ReadTableId(false);
+ if (!m_connected)
+ break;
+ UINT32 remoteTableId = input.ReadTableId(false);
+ if (!m_connected)
+ break;
+#ifdef DEBUG
+ char pbuf[64];
+ snprintf(pbuf, 64, "Table Assignment: local=%d remote=%d\n", localTableId, remoteTableId);
+ printf(pbuf);
+#endif
+ m_tableMap.insert(IDMap_t::value_type(remoteTableId, localTableId));
+ }
+ else if (value == kNetworkTables_ASSIGNMENT)
+ {
+ UINT32 tableId = input.ReadTableId(false);
+ if (!m_connected)
+ break;
+ NetworkTable *table = GetTable(false, tableId);
+ std::string keyName = input.ReadString();
+ if (!m_connected)
+ break;
+ Key *key = table->GetKey(keyName.c_str());
+ UINT32 id = input.ReadId(false);
+ if (!m_connected)
+ break;
+#ifdef DEBUG
+ char pbuf[64];
+ snprintf(pbuf, 64, "Field Assignment: table %d \"%s\" local=%d remote=%d\n", tableId, keyName.c_str(), key->GetId(), id);
+ printf(pbuf);
+#endif
+ m_fieldMap.insert(IDMap_t::value_type(id, key->GetId()));
+ }
+ else if (value == kNetworkTables_TRANSACTION)
+ {
+#ifdef DEBUG
+ printf("Transaction Start\n");
+#endif
+ m_inTransaction = !m_inTransaction;
+ // Finishing a transaction
+ if (!m_inTransaction)
+ {
+ if (m_denyTransaction)
+ {
+ Offer(std::auto_ptr<Data>(new Denial(1)));
+ }
+ else
+ {
+ if (!m_transaction->IsEmpty())
+ ((Entry *)m_transaction->Peek())->GetKey()->GetTable()->ProcessTransaction(false, m_transaction);
+ Offer(std::auto_ptr<Data>(new Confirmation(1)));
+ }
+ m_denyTransaction = false;
+ }
+#ifdef DEBUG
+ printf("Transaction End\n");
+#endif
+ }
+ else
+ {
+#ifdef DEBUG
+ char buf[64];
+ snprintf(buf, 64, "Don't know how to interpret marker byte (%02X)", value);
+ wpi_setWPIErrorWithContext(NetworkTablesCorrupt, buf);
+#else
+ wpi_setWPIErrorWithContext(NetworkTablesCorrupt, "Don't know how to interpret marker byte");
+#endif
+ Close();
+ return;
+ }
+ value = input.Read();
+ }
+}
+
+void Connection::WriteTaskRun()
+{
+ std::auto_ptr<Buffer> buffer = std::auto_ptr<Buffer>(new Buffer(2048));
+ bool sentData = true;
+ while (m_connected)
+ {
+ std::pair<Data *, bool> data;
+ {
+ Synchronized sync(m_dataLock);
+ data = m_queue->Poll();
+ // Check if there is no data to send
+ if (data.first == NULL)
+ {
+ // Ping if necessary
+ if (sentData)
+ {
+ sentData = false;
+ }
+ else
+ {
+ buffer->WriteByte(kNetworkTables_PING);
+ buffer->Flush(m_socket);
+ }
+ semGive(m_dataLock);
+ semTake(m_dataAvailable, kWriteDelay);
+ semTake(m_dataLock, WAIT_FOREVER);
+ continue;
+ }
+ }
+
+ // If there is data, send it
+ sentData = true;
+
+ if (data.first->IsEntry())
+ m_confirmations.push_back((Entry *)data.first);
+ else if (data.first->IsOldData())
+ m_confirmations.push_back(((OldData *)data.first)->GetEntry());
+ else if (data.first->IsTransaction())
+ m_confirmations.push_back((Entry *)NULL);
+
+ data.first->Encode(buffer.get());
+ buffer->Flush(m_socket);
+ // Noone else wants this data and it used to be auto_ptr'd, so delete it
+ if (data.second)
+ delete data.first;
+ }
+}
+
+void Connection::Close()
+{
+ if (m_connected)
+ {
+ m_connected = false;
+ close(m_socket);
+ WatchdogFeed();
+ IDMap_t::iterator it = m_tableMap.begin();
+ IDMap_t::iterator end = m_tableMap.end();
+ for (; it != end; it++)
+ {
+ // Get the local id
+ UINT32 id = it->second;
+ NetworkTable *table = NetworkTable::GetTable(id);
+#ifdef DEBUG
+ char pbuf[64];
+ snprintf(pbuf, 64, "Removing Table %d (%p)\n", id, table);
+ printf(pbuf);
+#endif
+ if (table)
+ table->RemoveConnection(this);
+ }
+
+ ConnectionManager::GetInstance()->RemoveConnection(this);
+ }
+}
+
+NetworkTable *Connection::GetTable(bool local, UINT32 id)
+{
+ NetworkTable *table = NULL;
+ if (local)
+ {
+ table = NetworkTable::GetTable(id);
+ }
+ else
+ {
+ IDMap_t::iterator localID = m_tableMap.find(id);
+ if (localID != m_tableMap.end())
+ {
+ table = NetworkTable::GetTable(localID->second);
+ }
+ /*
+ else
+ {
+ // This should not be needed as long as TABLE_REQUEST is always issued first
+ // We don't care about hosting locally anonymous tables from the network
+ table = new NetworkTable();
+ m_tableMap.insert(IDMap_t::value_type(id, table->GetId()));
+ Offer(std::auto_ptr<Data>(new TableAssignment(table, id)));
+ table->AddConnection(this);
+ }
+ */
+ }
+ if (table == NULL)
+ {
+ wpi_setWPIErrorWithContext(NetworkTablesCorrupt, "Unexpected ID");
+ }
+ return table;
+}
+
+bool Connection::ConfirmationsContainsKey(Key *key)
+{
+ std::deque<Entry *>::iterator it = m_confirmations.begin();
+ std::deque<Entry *>::iterator end = m_confirmations.end();
+ for (; it != end; it++)
+ if ((*it)->GetKey() == key)
+ return true;
+
+ return false;
+}
+
+void Connection::WatchdogTaskRun()
+{
+ Synchronized sync(m_watchdogLock);
+ while (m_connected)
+ {
+ while(!m_watchdogActive)
+ {
+ semGive(m_watchdogLock);
+ semTake(m_watchdogFood, WAIT_FOREVER);
+ semTake(m_watchdogLock, WAIT_FOREVER);
+ }
+ m_watchdogFed = false;
+ semGive(m_watchdogLock);
+ int retval = semTake(m_watchdogFood, kTimeout);
+ semTake(m_watchdogLock, WAIT_FOREVER);
+ if (retval == ERROR && !m_watchdogFed)
+ {
+ wpi_setWPIErrorWithContext(Timeout, "NetworkTables watchdog expired... disconnecting");
+ break;
+ }
+ }
+
+ Close();
+}
+
+void Connection::WatchdogActivate()
+{
+ Synchronized sync(m_watchdogLock);
+ if (!m_watchdogActive)
+ {
+ m_watchdogActive = true;
+ semGive(m_watchdogFood);
+ }
+}
+
+void Connection::WatchdogFeed()
+{
+ Synchronized sync(m_watchdogLock);
+ m_watchdogActive = false;
+ m_watchdogFed = true;
+ semGive(m_watchdogFood);
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Connection.h b/aos/externals/WPILib/WPILib/NetworkTables/Connection.h
new file mode 100644
index 0000000..50dbca7
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Connection.h
@@ -0,0 +1,82 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __CONNECTION_H__
+#define __CONNECTION_H__
+
+#include "ErrorBase.h"
+#include "Task.h"
+#include <map>
+#include <deque>
+
+class NetworkTable;
+
+namespace NetworkTables
+{
+class Data;
+class Entry;
+class Key;
+class NetworkQueue;
+class TransactionEnd;
+class TransactionStart;
+
+class Connection : public ErrorBase
+{
+ friend class ConnectionManager;
+ friend class NetworkTable;
+ friend class Reader;
+public:
+ static const UINT32 kWriteDelay = 250;
+ static const UINT32 kTimeout = 1000;
+
+private:
+ Connection(int socket);
+ ~Connection();
+ void OfferTransaction(NetworkQueue *transaction);
+ void Offer(Data *data);
+ void Offer(std::auto_ptr<Data> autoData);
+ void Start();
+ void ReadTaskRun();
+ void WriteTaskRun();
+ void Close();
+ bool IsConnected() {return m_connected;}
+ NetworkTable *GetTable(bool local, UINT32 id);
+ bool ConfirmationsContainsKey(Key *key);
+ void WatchdogActivate();
+ void WatchdogFeed();
+ void WatchdogTaskRun();
+
+ static int InitReadTask(Connection *obj) {obj->ReadTaskRun();return 0;}
+ static int InitWriteTask(Connection *obj) {obj->WriteTaskRun();return 0;}
+ static int InitWatchdogTask(Connection *obj) {obj->WatchdogTaskRun();return 0;}
+
+ int m_socket;
+ SEM_ID m_dataLock;
+ SEM_ID m_dataAvailable;
+ SEM_ID m_watchdogLock;
+ SEM_ID m_watchdogFood;
+ typedef std::map<UINT32, UINT32> IDMap_t;
+ IDMap_t m_tableMap;
+ IDMap_t m_fieldMap;
+ NetworkQueue *m_queue;
+ std::deque<Entry *> m_confirmations;
+ NetworkQueue *m_transaction;
+ bool m_connected;
+ bool m_inTransaction;
+ bool m_denyTransaction;
+ bool m_watchdogActive;
+ bool m_watchdogFed;
+ Task m_readTask;
+ Task m_writeTask;
+ Task m_watchdogTask;
+ TransactionStart *m_transactionStart;
+ TransactionEnd *m_transactionEnd;
+};
+
+} // namespace
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/ConnectionManager.cpp b/aos/externals/WPILib/WPILib/NetworkTables/ConnectionManager.cpp
new file mode 100644
index 0000000..1b1c816
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/ConnectionManager.cpp
@@ -0,0 +1,147 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/ConnectionManager.h"
+
+#include "NetworkTables/Connection.h"
+#include "NetworkTables/InterfaceConstants.h"
+#include "Synchronized.h"
+#include "WPIErrors.h"
+
+#include <inetLib.h>
+#include <selectLib.h>
+#include <semLib.h>
+#include <sockLib.h>
+#include <taskLib.h>
+#include <usrLib.h>
+
+#define kPort 1735
+
+namespace NetworkTables
+{
+
+ConnectionManager *ConnectionManager::_instance = NULL;
+
+ConnectionManager::ConnectionManager() :
+ m_isServer(true),
+ m_listener("NetworkTablesListener", (FUNCPTR)InitListenTask),
+ m_run(true),
+ m_listenSocket(-1),
+ m_connectionLock(NULL)
+{
+ AddToSingletonList();
+ m_connectionLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+ m_listener.Start((UINT32)this);
+}
+
+ConnectionManager::~ConnectionManager()
+{
+ close(m_listenSocket);
+ _instance->m_run = false;
+ while(_instance->m_listener.Verify())
+ taskDelay(10);
+ semTake(m_connectionLock, WAIT_FOREVER);
+ m_connections.clear();
+ semDelete(m_connectionLock);
+}
+
+ConnectionManager *ConnectionManager::GetInstance()
+{
+ if (_instance == NULL)
+ _instance = new ConnectionManager();
+ return _instance;
+}
+
+int ConnectionManager::ListenTaskRun()
+{
+ struct sockaddr_in serverAddr;
+ int sockAddrSize = sizeof(serverAddr);
+ bzero((char *)&serverAddr, sockAddrSize);
+ serverAddr.sin_len = (u_char)sockAddrSize;
+ serverAddr.sin_family = AF_INET;
+ serverAddr.sin_port = htons(kPort);
+ serverAddr.sin_addr.s_addr = htonl(INADDR_ANY);
+
+ // Create the socket.
+ if ((m_listenSocket = socket(AF_INET, SOCK_STREAM, 0)) == ERROR)
+ {
+ printErrno(0);
+ wpi_setGlobalWPIErrorWithContext(ResourceAlreadyAllocated, "Could not create NetworkTables server socket");
+ return -1;
+ }
+
+ // Set the TCP socket so that it can be reused if it is in the wait state.
+ int reuseAddr = 1;
+ setsockopt(m_listenSocket, SOL_SOCKET, SO_REUSEADDR, (char *)&reuseAddr, sizeof(reuseAddr));
+
+ // Bind socket to local address.
+ if (bind(m_listenSocket, (struct sockaddr *)&serverAddr, sockAddrSize) == ERROR)
+ {
+ close(m_listenSocket);
+ printErrno(0);
+ wpi_setGlobalWPIErrorWithContext(ResourceAlreadyAllocated, "Could not bind NetworkTables server socket");
+ return -1;
+ }
+
+ if (listen(m_listenSocket, 1) == ERROR)
+ {
+ close(m_listenSocket);
+ printErrno(0);
+ wpi_setGlobalWPIErrorWithContext(ResourceAlreadyAllocated, "Could not listen on NetworkTables server socket");
+ return -1;
+ }
+
+ struct timeval timeout;
+ // Check for a shutdown once per second
+ timeout.tv_sec = 1;
+ timeout.tv_usec = 0;
+ while (m_run)
+ {
+ fd_set fdSet;
+
+ FD_ZERO(&fdSet);
+ FD_SET(m_listenSocket, &fdSet);
+ if (select(FD_SETSIZE, &fdSet, NULL, NULL, &timeout) > 0)
+ {
+ if (FD_ISSET(m_listenSocket, &fdSet))
+ {
+ struct sockaddr clientAddr;
+ int clientAddrSize;
+ int connectedSocket = accept(m_listenSocket, &clientAddr, &clientAddrSize);
+ if (connectedSocket == ERROR)
+ continue;
+
+ // TODO: Linger option?
+ AddConnection(new Connection(connectedSocket));
+ }
+ }
+ }
+ return 0;
+}
+
+void ConnectionManager::AddConnection(Connection *connection)
+{
+ {
+ Synchronized sync(m_connectionLock);
+ if (!m_connections.insert(connection).second)
+ {
+ wpi_setGlobalWPIErrorWithContext(ResourceAlreadyAllocated, "Connection object already exists");
+ return;
+ }
+ }
+ connection->Start();
+}
+
+void ConnectionManager::RemoveConnection(Connection *connection)
+{
+ {
+ Synchronized sync(m_connectionLock);
+ m_connections.erase(connection);
+ }
+ delete connection;
+}
+
+}
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/ConnectionManager.h b/aos/externals/WPILib/WPILib/NetworkTables/ConnectionManager.h
new file mode 100644
index 0000000..d3883fb
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/ConnectionManager.h
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __CONNECTION_MANAGER_H__
+#define __CONNECTION_MANAGER_H__
+
+#include "NetworkTables/Data.h"
+#include "SensorBase.h"
+#include "Task.h"
+#include <set>
+
+namespace NetworkTables
+{
+class Connection;
+
+class ConnectionManager : public SensorBase
+{
+ friend class Connection;
+public:
+ static ConnectionManager *GetInstance();
+
+private:
+ ConnectionManager();
+ ~ConnectionManager();
+
+ int ListenTaskRun();
+ bool IsServer() {return m_isServer;}
+ void AddConnection(Connection *connection);
+ void RemoveConnection(Connection *connection);
+
+ static int InitListenTask(ConnectionManager *obj) {obj->ListenTaskRun();return 0;}
+
+ typedef std::set<Connection *> ConnectionSet;
+ bool m_isServer;
+ ConnectionSet m_connections;
+ Task m_listener;
+ bool m_run;
+ int m_listenSocket;
+ SEM_ID m_connectionLock;
+
+ static ConnectionManager *_instance;
+};
+
+}
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Data.cpp b/aos/externals/WPILib/WPILib/NetworkTables/Data.cpp
new file mode 100644
index 0000000..dc76bcd
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Data.cpp
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/Data.h"
+
+namespace NetworkTables
+{
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Data.h b/aos/externals/WPILib/WPILib/NetworkTables/Data.h
new file mode 100644
index 0000000..7b47877
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Data.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __DATA_H__
+#define __DATA_H__
+
+namespace NetworkTables
+{
+
+class Buffer;
+
+class Data {
+public:
+ virtual void Encode(Buffer *buffer) = 0;
+ virtual bool IsEntry() {return false;}
+ virtual bool IsOldData() {return false;}
+ virtual bool IsTransaction() {return false;}
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Denial.cpp b/aos/externals/WPILib/WPILib/NetworkTables/Denial.cpp
new file mode 100644
index 0000000..38292e3
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Denial.cpp
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/Denial.h"
+#include "NetworkTables/Buffer.h"
+#include "NetworkTables/InterfaceConstants.h"
+
+namespace NetworkTables
+{
+
+Denial::Denial(int count) :
+ m_count(count)
+{
+}
+
+void Denial::Encode(Buffer *buffer)
+{
+ for (int i = m_count; i > 0; i -= kNetworkTables_DENIAL - 1)
+ buffer->WriteByte(kNetworkTables_DENIAL | std::min(kNetworkTables_DENIAL - 1, i));
+}
+
+// Currently unused
+Denial *Denial::Combine(Denial *a, Denial *b)
+{
+ a->m_count = a->m_count + b->m_count;
+ delete b;
+ return a;
+}
+
+}
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Denial.h b/aos/externals/WPILib/WPILib/NetworkTables/Denial.h
new file mode 100644
index 0000000..595d322
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Denial.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __DENIAL_H__
+#define __DENIAL_H__
+
+#include "NetworkTables/Data.h"
+
+namespace NetworkTables
+{
+
+class Buffer;
+
+class Denial : public Data
+{
+public:
+ Denial(int count);
+ virtual void Encode(Buffer *buffer);
+private:
+ static Denial *Combine(Denial *a, Denial *b);
+
+ int m_count;
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/DoubleEntry.cpp b/aos/externals/WPILib/WPILib/NetworkTables/DoubleEntry.cpp
new file mode 100644
index 0000000..a1c1a74
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/DoubleEntry.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/DoubleEntry.h"
+#include "NetworkTables/Buffer.h"
+
+namespace NetworkTables
+{
+
+DoubleEntry::DoubleEntry(double value) :
+ m_value(value)
+{
+}
+
+NetworkTables_Types DoubleEntry::GetType()
+{
+ return kNetworkTables_Types_DOUBLE;
+}
+
+void DoubleEntry::Encode(Buffer *buffer)
+{
+ Entry::Encode(buffer);
+ buffer->WriteByte(kNetworkTables_DOUBLE);
+ buffer->WriteDouble(m_value);
+}
+
+double DoubleEntry::GetDouble()
+{
+ return m_value;
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/DoubleEntry.h b/aos/externals/WPILib/WPILib/NetworkTables/DoubleEntry.h
new file mode 100644
index 0000000..6108f0d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/DoubleEntry.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __DOUBLE_ENTRY_H__
+#define __DOUBLE_ENTRY_H__
+
+#include "NetworkTables/Entry.h"
+#include "NetworkTables/InterfaceConstants.h"
+#include <vxWorks.h>
+
+class NetworkTable;
+
+namespace NetworkTables
+{
+
+class Buffer;
+
+class DoubleEntry : public Entry {
+public:
+ DoubleEntry(double value);
+ virtual NetworkTables_Types GetType();
+ virtual void Encode(Buffer *buffer);
+ virtual double GetDouble();
+
+private:
+ double m_value;
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Entry.cpp b/aos/externals/WPILib/WPILib/NetworkTables/Entry.cpp
new file mode 100644
index 0000000..2c3d87a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Entry.cpp
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/Entry.h"
+#include "NetworkTables/Key.h"
+#include "WPIErrors.h"
+
+namespace NetworkTables
+{
+
+UINT32 Entry::GetId()
+{
+ return m_key->GetId();
+}
+
+void Entry::Encode(Buffer *buffer)
+{
+ GetKey()->EncodeName(buffer);
+}
+
+int Entry::GetInt()
+{
+ wpi_setWPIError(NetworkTablesWrongType);
+ return 0;
+}
+
+double Entry::GetDouble()
+{
+ wpi_setWPIError(NetworkTablesWrongType);
+ return 0.0;
+}
+
+bool Entry::GetBoolean()
+{
+ wpi_setWPIError(NetworkTablesWrongType);
+ return false;
+}
+
+int Entry::GetString(char *str, int len)
+{
+ wpi_setWPIError(NetworkTablesWrongType);
+ return 0;
+}
+
+std::string Entry::GetString()
+{
+ wpi_setWPIError(NetworkTablesWrongType);
+ return "";
+}
+
+NetworkTable *Entry::GetTable()
+{
+ wpi_setWPIError(NetworkTablesWrongType);
+ return NULL;
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Entry.h b/aos/externals/WPILib/WPILib/NetworkTables/Entry.h
new file mode 100644
index 0000000..61ff5f8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Entry.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __ENTRY_H__
+#define __ENTRY_H__
+
+#include "ErrorBase.h"
+#include "NetworkTables/Data.h"
+#include "NetworkTables/InterfaceConstants.h"
+#include <vxWorks.h>
+
+class NetworkTable;
+
+namespace NetworkTables
+{
+
+class Buffer;
+class Connection;
+class Key;
+
+class Entry : public Data, public ErrorBase
+{
+public:
+ void SetKey(Key *key) {m_key = key;}
+ Key *GetKey() {return m_key;}
+ UINT32 GetId();
+ void SetSource(Connection *source) {m_source = source;}
+ Connection *GetSource() {return m_source;}
+
+ virtual void Encode(Buffer *buffer);
+ virtual bool IsEntry() {return true;}
+
+ virtual NetworkTables_Types GetType() = 0;
+ virtual int GetInt();
+ virtual double GetDouble();
+ virtual bool GetBoolean();
+ virtual int GetString(char *str, int len);
+ virtual std::string GetString();
+ virtual NetworkTable *GetTable();
+
+private:
+
+ Key *m_key;
+ Connection *m_source;
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/IntegerEntry.cpp b/aos/externals/WPILib/WPILib/NetworkTables/IntegerEntry.cpp
new file mode 100644
index 0000000..3806ac6
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/IntegerEntry.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/IntegerEntry.h"
+#include "NetworkTables/Buffer.h"
+
+namespace NetworkTables
+{
+
+IntegerEntry::IntegerEntry(int value) :
+ m_value(value)
+{
+}
+
+NetworkTables_Types IntegerEntry::GetType()
+{
+ return kNetworkTables_Types_INT;
+}
+
+void IntegerEntry::Encode(Buffer *buffer)
+{
+ Entry::Encode(buffer);
+ buffer->WriteByte(kNetworkTables_INT);
+ buffer->WriteInt(m_value);
+}
+
+int IntegerEntry::GetInt()
+{
+ return m_value;
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/IntegerEntry.h b/aos/externals/WPILib/WPILib/NetworkTables/IntegerEntry.h
new file mode 100644
index 0000000..bee5a7e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/IntegerEntry.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __INTEGER_ENTRY_H__
+#define __INTEGER_ENTRY_H__
+
+#include "NetworkTables/Entry.h"
+#include "NetworkTables/InterfaceConstants.h"
+#include <vxWorks.h>
+
+class NetworkTable;
+
+namespace NetworkTables
+{
+
+class Buffer;
+
+class IntegerEntry : public Entry {
+public:
+ IntegerEntry(int value);
+ virtual NetworkTables_Types GetType();
+ virtual void Encode(Buffer *buffer);
+ virtual int GetInt();
+
+private:
+ int m_value;
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/InterfaceConstants.h b/aos/externals/WPILib/WPILib/NetworkTables/InterfaceConstants.h
new file mode 100644
index 0000000..99a0eb2
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/InterfaceConstants.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __INTERFACE_CONSTANTS_H__
+#define __INTERFACE_CONSTANTS_H__
+
+#define kNetworkTables_STRING 0
+#define kNetworkTables_BEGIN_STRING 0xFF
+#define kNetworkTables_END_STRING 0
+#define kNetworkTables_INT 1
+#define kNetworkTables_DOUBLE 2
+#define kNetworkTables_TABLE 3
+#define kNetworkTables_TABLE_ASSIGNMENT kNetworkTables_TABLE
+#define kNetworkTables_BOOLEAN_FALSE 4
+#define kNetworkTables_BOOLEAN_TRUE 5
+#define kNetworkTables_ASSIGNMENT 6
+#define kNetworkTables_EMPTY 7
+#define kNetworkTables_DATA 8
+#define kNetworkTables_OLD_DATA 9
+#define kNetworkTables_TRANSACTION 10
+#define kNetworkTables_REMOVAL 11
+#define kNetworkTables_TABLE_REQUEST 12
+#define kNetworkTables_ID (1 << 7)
+#define kNetworkTables_TABLE_ID (1 << 6)
+#define kNetworkTables_CONFIRMATION (1 << 5)
+#define kNetworkTables_CONFIRMATION_MAX (kNetworkTables_CONFIRMATION - 1)
+#define kNetworkTables_PING kNetworkTables_CONFIRMATION
+#define kNetworkTables_DENIAL (1 << 4)
+
+typedef enum
+{
+ kNetworkTables_Types_NONE = -1,
+ kNetworkTables_Types_STRING = kNetworkTables_STRING,
+ kNetworkTables_Types_INT = kNetworkTables_INT,
+ kNetworkTables_Types_DOUBLE = kNetworkTables_DOUBLE,
+ kNetworkTables_Types_BOOLEAN = kNetworkTables_BOOLEAN_TRUE,
+ kNetworkTables_Types_TABLE = kNetworkTables_TABLE,
+} NetworkTables_Types;
+
+#endif // __INTERFACE_CONSTANTS_H__
+
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Key.cpp b/aos/externals/WPILib/WPILib/NetworkTables/Key.cpp
new file mode 100644
index 0000000..b61b23e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Key.cpp
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/Key.h"
+
+#include "NetworkTables/Buffer.h"
+#include "NetworkTables/Entry.h"
+#include "NetworkTables/NetworkTable.h"
+#include "Synchronized.h"
+
+namespace NetworkTables
+{
+
+SEM_ID Key::_staticLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);;
+std::map<UINT32, Key *> Key::_idsMap;
+UINT32 Key::_currentId = 0;
+
+Key::Key(NetworkTable *table, const char *keyName) :
+ m_table(table),
+ m_name(keyName),
+ m_entry(NULL),
+ m_id(AllocateId())
+{
+ _idsMap.insert(std::pair<UINT32, Key *>(m_id, this));
+}
+
+Key::~Key()
+{
+ _idsMap.erase(m_id);
+}
+
+NetworkTables_Types Key::GetType()
+{
+ if (m_entry.get() == NULL)
+ return kNetworkTables_Types_NONE;
+ return m_entry->GetType();
+}
+
+void Key::Encode(Buffer *buffer)
+{
+ buffer->WriteByte(kNetworkTables_ASSIGNMENT);
+ m_table->EncodeName(buffer);
+ buffer->WriteString(m_name);
+ buffer->WriteId(m_id);
+}
+
+std::auto_ptr<Entry> Key::SetEntry(std::auto_ptr<Entry> entry)
+{
+ Entry *old = m_entry.release();
+ m_entry = entry;
+ m_entry->SetKey(this);
+ return std::auto_ptr<Entry>(old);
+}
+
+Key *Key::GetKey(UINT32 id)
+{
+ return _idsMap[id];
+}
+
+void Key::EncodeName(Buffer *buffer)
+{
+ buffer->WriteId(m_id);
+}
+
+UINT32 Key::AllocateId()
+{
+ Synchronized sync(_staticLock);
+ return ++_currentId;
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Key.h b/aos/externals/WPILib/WPILib/NetworkTables/Key.h
new file mode 100644
index 0000000..07a5fa7
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Key.h
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __KEY_H__
+#define __KEY_H__
+
+#include "NetworkTables/Data.h"
+#include "NetworkTables/InterfaceConstants.h"
+
+#include <map>
+#include <string>
+
+class NetworkTable;
+
+namespace NetworkTables
+{
+
+class Entry;
+
+class Key : public Data
+{
+ friend class Connection;
+ friend class Entry;
+ friend class KeyConnectionListener;
+ friend class NetworkTable;
+public:
+ Key(NetworkTable *table, const char *keyName);
+ virtual ~Key();
+ NetworkTable *GetTable() {return m_table;}
+ NetworkTables_Types GetType();
+ Entry *GetEntry() {return m_entry.get();}
+ std::string GetName() {return m_name;}
+ UINT32 GetId() {return m_id;}
+ void Encode(Buffer *buffer);
+
+ static Key *GetKey(UINT32 id);
+
+private:
+ std::auto_ptr<Entry> SetEntry(std::auto_ptr<Entry> entry);
+ bool HasEntry() {return m_entry.get() != NULL;}
+ void EncodeName(Buffer *buffer);
+
+ static UINT32 AllocateId();
+
+ NetworkTable *m_table;
+ std::string m_name;
+ // Keys are responsible for entrys' memory
+ std::auto_ptr<Entry> m_entry;
+ UINT32 m_id;
+
+ static SEM_ID _staticLock;
+ static std::map<UINT32, Key *> _idsMap;
+ static UINT32 _currentId;
+};
+
+} // namespace
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/NetworkQueue.cpp b/aos/externals/WPILib/WPILib/NetworkTables/NetworkQueue.cpp
new file mode 100644
index 0000000..2eac671
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/NetworkQueue.cpp
@@ -0,0 +1,133 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/NetworkQueue.h"
+
+#include "NetworkTables/Entry.h"
+#include "NetworkTables/Key.h"
+#include "NetworkTables/Confirmation.h"
+#include "NetworkTables/Denial.h"
+#include "NetworkTables/TransactionStart.h"
+#include "NetworkTables/TransactionEnd.h"
+#include "Synchronized.h"
+
+namespace NetworkTables
+{
+
+NetworkQueue::NetworkQueue() :
+ m_dataLock(NULL),
+ m_inTransaction(false)
+{
+ m_dataLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+}
+
+NetworkQueue::~NetworkQueue()
+{
+ semDelete(m_dataLock);
+}
+
+void NetworkQueue::Offer(TransactionStart *value)
+{
+ Synchronized sync(m_dataLock);
+ m_inTransaction = true;
+ m_dataQueue.push_back(DataQueue_t::value_type(value, false));
+}
+
+void NetworkQueue::Offer(TransactionEnd *value)
+{
+ Synchronized sync(m_dataLock);
+ m_inTransaction = false;
+ m_dataQueue.push_back(DataQueue_t::value_type(value, false));
+}
+
+void NetworkQueue::Offer(Data *value, bool needsDelete)
+{
+ Synchronized sync(m_dataLock);
+ if (value->IsEntry())
+ {
+ if (m_inTransaction)
+ {
+ m_dataQueue.push_back(DataQueue_t::value_type(value, needsDelete));
+ }
+ else
+ {
+ DataHash_t::iterator found = m_latestDataHash.find(((Entry *)value)->GetId());
+ if (found != m_latestDataHash.end())
+ {
+ // Replace the old value for this key with a new one
+ // If this used to be auto_ptr'd, then delete it
+ // (This should never happen, right?)
+ if (found->second->second)
+ delete found->second->first;
+ found->second->first = value;
+ }
+ else
+ {
+ // Add a new entry to the queue
+ m_dataQueue.push_back(DataQueue_t::value_type(value, needsDelete));
+ m_latestDataHash.insert(DataHash_t::value_type(((Entry *)m_dataQueue.back().first)->GetId(), m_dataQueue.end() - 1));
+ }
+ }
+ }
+ else
+ {
+ // TODO: Combine Confirmations
+ // TODO: Combine Denials
+ m_dataQueue.push_back(DataQueue_t::value_type(value, needsDelete));
+ }
+}
+
+void NetworkQueue::Offer(std::auto_ptr<Data> value)
+{
+ // Indicate that we released this from an auto_ptr
+ Offer(value.release(), true);
+}
+
+bool NetworkQueue::IsEmpty()
+{
+ Synchronized sync(m_dataLock);
+ return m_dataQueue.empty();
+}
+
+bool NetworkQueue::ContainsKey(Key *key)
+{
+ Synchronized sync(m_dataLock);
+ DataHash_t::iterator found = m_latestDataHash.find(key->GetId());
+ return key != NULL && found != m_latestDataHash.end();
+}
+
+// @return the data and if it came from an auto_ptr
+std::pair<Data *, bool> NetworkQueue::Poll()
+{
+ Synchronized sync(m_dataLock);
+ if (IsEmpty())
+ return DataQueue_t::value_type(NULL, false);
+ DataQueue_t::value_type data = m_dataQueue.front();
+ if (data.first->IsEntry())
+ {
+ m_latestDataHash.erase(((Entry *)data.first)->GetId());
+ }
+ m_dataQueue.pop_front();
+ return data;
+}
+
+void NetworkQueue::Clear()
+{
+ Synchronized sync(m_dataLock);
+ m_dataQueue.clear();
+ m_latestDataHash.clear();
+}
+
+Data *NetworkQueue::Peek()
+{
+ Synchronized sync(m_dataLock);
+ if (IsEmpty())
+ return NULL;
+ return m_dataQueue.front().first;
+}
+
+} // namespace
+
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/NetworkQueue.h b/aos/externals/WPILib/WPILib/NetworkTables/NetworkQueue.h
new file mode 100644
index 0000000..ec9da58
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/NetworkQueue.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __NETWORK_QUEUE_H__
+#define __NETWORK_QUEUE_H__
+
+#include "NetworkTables/NetworkTable.h"
+#include <map>
+#include <deque>
+
+namespace NetworkTables
+{
+class Entry;
+class Confirmation;
+class Denial;
+class TransactionStart;
+class TransactionEnd;
+class Data;
+
+class NetworkQueue
+{
+ typedef std::deque<std::pair<Data *, bool> > DataQueue_t;
+ typedef std::map<UINT32, DataQueue_t::iterator> DataHash_t;
+public:
+ NetworkQueue();
+ ~NetworkQueue();
+
+ void Offer(TransactionStart *value);
+ void Offer(TransactionEnd *value);
+ void Offer(Data *value, bool needsDelete=false);
+ void Offer(std::auto_ptr<Data> value);
+ bool IsEmpty();
+ bool ContainsKey(Key *key);
+ std::pair<Data *, bool> Poll();
+ void Clear();
+ Data *Peek();
+ DataQueue_t::const_iterator GetQueueHead() {return m_dataQueue.begin();}
+ bool IsQueueEnd(DataQueue_t::const_iterator it) {return m_dataQueue.end() == it;}
+
+private:
+ SEM_ID m_dataLock;
+ DataQueue_t m_dataQueue;
+ DataHash_t m_latestDataHash;
+ bool m_inTransaction;
+};
+
+}
+
+#endif // __NETWORK_QUEUE_H__
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/NetworkTable.cpp b/aos/externals/WPILib/WPILib/NetworkTables/NetworkTable.cpp
new file mode 100644
index 0000000..e236fa8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/NetworkTable.cpp
@@ -0,0 +1,683 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/NetworkTable.h"
+
+#include "NetworkTables/BooleanEntry.h"
+#include "NetworkTables/Buffer.h"
+#include "NetworkTables/Connection.h"
+#include "NetworkTables/ConnectionManager.h"
+#include "NetworkTables/DoubleEntry.h"
+#include "NetworkTables/Entry.h"
+#include "NetworkTables/IntegerEntry.h"
+#include "NetworkTables/Key.h"
+#include "NetworkTables/NetworkQueue.h"
+#include "NetworkTables/NetworkTableChangeListener.h"
+#include "NetworkTables/NetworkTableAdditionListener.h"
+#include "NetworkTables/NetworkTableConnectionListener.h"
+#include "NetworkTables/StringEntry.h"
+#include "NetworkTables/TableEntry.h"
+#include "Synchronized.h"
+#include "WPIErrors.h"
+
+NetworkTable::TableNameMap NetworkTable::_tableNameMap;
+NetworkTable::TableIdMap NetworkTable::_tableIdMap;
+UINT32 NetworkTable::_currentId = 1;
+bool NetworkTable::_initialized = false;
+SEM_ID NetworkTable::_staticMemberMutex = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+
+NetworkTable::NetworkTable() :
+ m_dataLock(NULL),
+ m_listenerLock(NULL),
+ m_id(GrabId()),
+ m_transaction(NULL),
+ m_transactionCount(0),
+ m_hasChanged(NULL),
+ m_hasAdded(NULL)
+{
+ m_dataLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+ m_listenerLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+ m_transaction = new NetworkTables::NetworkQueue();
+ m_hasChanged = new NetworkTables::NetworkQueue();
+ m_hasAdded = new NetworkTables::NetworkQueue();
+}
+
+NetworkTable::~NetworkTable()
+{
+ delete m_hasAdded;
+ delete m_hasChanged;
+ delete m_transaction;
+ semTake(m_listenerLock, WAIT_FOREVER);
+ m_connectionListeners.clear();
+ m_additionListeners.clear();
+ m_listeners.clear();
+ m_listenToAllListeners.clear();
+ semDelete(m_listenerLock);
+ semTake(m_dataLock, WAIT_FOREVER);
+ m_connections.clear();
+ m_data.clear();
+ semDelete(m_dataLock);
+}
+
+/**
+ * Opens up the connection stream. Note that this method will be called
+ * automatically when {@link NetworkTable#GetTable(const char *)} is
+ * called. This will only have an effect the first time this is called.
+ */
+void NetworkTable::Initialize()
+{
+ if (!_initialized)
+ {
+ _initialized = true;
+ NetworkTables::ConnectionManager::GetInstance();
+ }
+}
+
+/**
+ * Returns the table with the given name. The table will automatically be connected
+ * by clients asking for the same table.
+ * @param tableName The name of the table
+ * @return The table
+ */
+NetworkTable *NetworkTable::GetTable(const char *tableName)
+{
+ Initialize();
+ Synchronized sync(_staticMemberMutex);
+ // Insert will add a new element if the key is not found
+ // or will return the existing key if it is found.
+ std::pair<TableNameMap::iterator, bool> ret =
+ _tableNameMap.insert(TableNameMap::value_type(tableName, NULL));
+ if (ret.second)
+ // Key not found. Create a table.
+ ret.first->second = new NetworkTable();
+ return ret.first->second;
+}
+
+NetworkTable *NetworkTable::GetTable(int id)
+{
+ Synchronized sync(_staticMemberMutex);
+ // Don't check if the id is in the map(assume it is)
+ // If it's not, we will get the ID mapped to an uninitialized pointer (bad)
+ // TODO: Validate success and error if not found
+ return _tableIdMap[id];
+}
+
+std::vector<const char *> NetworkTable::GetKeys()
+{
+ Synchronized sync(m_dataLock);
+ std::vector<const char *> keys;
+ keys.reserve(m_data.size());
+ DataMap::iterator it = m_data.begin();
+ DataMap::iterator end = m_data.end();
+ for (; it != end; it++)
+ if (it->second->HasEntry())
+ keys.push_back(it->second->GetName().c_str());
+ return keys;
+}
+
+/**
+ * Begins a transaction. Note that you must call endTransaction() afterwards.
+ */
+void NetworkTable::BeginTransaction()
+{
+ Synchronized sync(m_dataLock);
+ m_transactionCount++;
+}
+
+void NetworkTable::EndTransaction()
+{
+ Synchronized sync(m_dataLock);
+ if (m_transactionCount == 0)
+ {
+ wpi_setWPIErrorWithContext(NetworkTablesCorrupt, "EndTransaction() called too many times");
+ return;
+ }
+ else if (--m_transactionCount == 0)
+ {
+ ProcessTransaction(true, m_transaction);
+ }
+}
+
+/**
+ * Adds a NetworkTableChangeListener to listen to the specified element.
+ * @param keyName the key to listen to
+ * @param listener the listener
+ * @see NetworkTableChangeListener
+ */
+void NetworkTable::AddChangeListener(const char *keyName, NetworkTableChangeListener *listener)
+{
+ Synchronized sync(m_listenerLock);
+ std::set<NetworkTableChangeListener *> emptyList;
+ std::pair<ListenersMap::iterator, bool> listenersForKey =
+ m_listeners.insert(ListenersMap::value_type(keyName, emptyList));
+ listenersForKey.first->second.insert(listener);
+}
+
+/**
+ * Adds a NetworkTableChangeListener to listen to any element changed in the table
+ * @param listener the listener
+ * @see NetworkTableChangeListener
+ */
+void NetworkTable::AddChangeListenerAny(NetworkTableChangeListener *listener)
+{
+ Synchronized sync(m_listenerLock);
+ m_listenToAllListeners.insert(listener);
+}
+
+/**
+ * Removes the given NetworkTableChangeListener from the specified element.
+ * @param keyName the key to no longer listen to.
+ * @param listener the listener to remove
+ * @see NetworkTableChangeListener
+ */
+void NetworkTable::RemoveChangeListener(const char *keyName,
+ NetworkTableChangeListener *listener)
+{
+ Synchronized sync(m_listenerLock);
+ ListenersMap::iterator listenersForKey = m_listeners.find(keyName);
+ if (listenersForKey != m_listeners.end())
+ listenersForKey->second.erase(listener);
+}
+
+/**
+ * Removes the given NetworkTableChangeListener for any element in the table.
+ * @param listener the listener to remove
+ * @see NetworkTableChangeListener
+ */
+void NetworkTable::RemoveChangeListenerAny(NetworkTableChangeListener *listener)
+{
+ Synchronized sync(m_listenerLock);
+ m_listenToAllListeners.erase(listener);
+}
+
+/**
+ * Adds the NetworkTableAdditionListener to the table.
+ * @param listener the listener to add
+ * @see NetworkTableAdditionListener
+ */
+void NetworkTable::AddAdditionListener(NetworkTableAdditionListener *listener)
+{
+ Synchronized sync(m_listenerLock);
+ m_additionListeners.insert(listener);
+}
+
+/**
+ * Removes the given NetworkTableAdditionListener from the set of listeners.
+ * @param listener the listener to remove
+ * @see NetworkTableAdditionListener
+ */
+void NetworkTable::RemoveAdditionListener(
+ NetworkTableAdditionListener *listener)
+{
+ Synchronized sync(m_listenerLock);
+ m_additionListeners.erase(listener);
+}
+
+/**
+ * Adds a NetworkTableConnectionListener to this table.
+ * @param listener the listener to add
+ * @param immediateNotify whether to tell the listener of the current connection status
+ * @see NetworkTableConnectionListener
+ */
+void NetworkTable::AddConnectionListener(
+ NetworkTableConnectionListener *listener, bool immediateNotify)
+{
+ Synchronized sync(m_listenerLock);
+ m_connectionListeners.insert(listener);
+}
+
+/**
+ * Removes the given NetworkTableConnectionListener from the table.
+ * @param listener the listener to remove
+ * @see NetworkTableConnectionListener
+ */
+void NetworkTable::RemoveConnectionListener(
+ NetworkTableConnectionListener *listener)
+{
+ Synchronized sync(m_listenerLock);
+ m_connectionListeners.erase(listener);
+}
+
+/**
+ * Returns whether or not this table is connected to the robot.
+ *
+ * @return whether or not this table is connected to the robot
+ */
+bool NetworkTable::IsConnected()
+{
+ Synchronized sync(m_dataLock);
+ return m_connections.size() > 0;
+}
+
+bool NetworkTable::ContainsKey(const char *keyName)
+{
+ if (keyName == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "keyName");
+ return false;
+ }
+ Synchronized sync(m_dataLock);
+ DataMap::iterator key = m_data.find(keyName);
+ return key != m_data.end() && key->second->HasEntry();
+}
+
+/**
+ * Internally used to get at the underlying Entry
+ * @param keyName the name of the key
+ * @return the entry at that position (or null if no entry)
+ */
+NetworkTables::Entry *NetworkTable::GetEntry(const char *keyName)
+{
+ if (keyName == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "keyName");
+ return NULL;
+ }
+ Synchronized sync(m_dataLock);
+ DataMap::iterator key = m_data.find(keyName);
+ if (key == m_data.end())
+ return NULL;
+ return key->second->GetEntry();
+}
+
+/**
+ * Returns the value at the specified key.
+ * @param keyName the key
+ * @return the value
+ */
+int NetworkTable::GetInt(const char *keyName)
+{
+ NetworkTables::Entry *entry = GetEntry(keyName);
+ if (entry != NULL)
+ {
+ if (entry->GetType() == kNetworkTables_Types_INT)
+ return entry->GetInt();
+ else
+ wpi_setWPIError(NetworkTablesWrongType);
+ }
+ return 0;
+}
+
+/**
+ * Returns the value at the specified key.
+ * @param keyName the key
+ * @return the value
+ */
+bool NetworkTable::GetBoolean(const char *keyName)
+{
+ NetworkTables::Entry *entry = GetEntry(keyName);
+ if (entry != NULL)
+ {
+ if (entry->GetType() == kNetworkTables_Types_BOOLEAN)
+ return entry->GetBoolean();
+ else
+ wpi_setWPIError(NetworkTablesWrongType);
+ }
+ return false;
+}
+
+/**
+ * Returns the value at the specified key.
+ * @param keyName the key
+ * @return the value
+ */
+double NetworkTable::GetDouble(const char *keyName)
+{
+ NetworkTables::Entry *entry = GetEntry(keyName);
+ if (entry != NULL)
+ {
+ if (entry->GetType() == kNetworkTables_Types_DOUBLE)
+ return entry->GetDouble();
+ else
+ wpi_setWPIError(NetworkTablesWrongType);
+ }
+ return 0.0;
+}
+
+/**
+ * Returns the value at the specified key.
+ * @param keyName the key
+ * @return the value
+ */
+int NetworkTable::GetString(const char *keyName, char *value, int len)
+{
+ NetworkTables::Entry *entry = GetEntry(keyName);
+ if (entry != NULL)
+ {
+ if (entry->GetType() == kNetworkTables_Types_STRING)
+ return entry->GetString(value, len);
+ else
+ wpi_setWPIError(NetworkTablesWrongType);
+ }
+ return 0;
+}
+
+std::string NetworkTable::GetString(std::string keyName)
+{
+ NetworkTables::Entry *entry = GetEntry(keyName.c_str());
+ if (entry != NULL)
+ {
+ if (entry->GetType() == kNetworkTables_Types_STRING)
+ return entry->GetString();
+ else
+ wpi_setWPIError(NetworkTablesWrongType);
+ }
+ return "";
+}
+
+
+/**
+ * Returns the value at the specified key.
+ * @param keyName the key
+ * @return the value
+ */
+NetworkTable *NetworkTable::GetSubTable(const char *keyName)
+{
+ NetworkTables::Entry *entry = GetEntry(keyName);
+ if (entry != NULL)
+ {
+ if (entry->GetType() == kNetworkTables_Types_TABLE)
+ return entry->GetTable();
+ else
+ wpi_setWPIError(NetworkTablesWrongType);
+ }
+ return NULL;
+}
+
+/**
+ * Maps the specified key to the specified value in this table.
+ * Neither the key nor the value can be null.
+ * The value can be retrieved by calling the get method with a key that is equal to the original key.
+ * @param keyName the key
+ * @param value the value
+ */
+void NetworkTable::PutInt(const char *keyName, int value)
+{
+ Put(keyName, std::auto_ptr<NetworkTables::Entry>(new NetworkTables::IntegerEntry(value)));
+}
+
+/**
+ * Maps the specified key to the specified value in this table.
+ * Neither the key nor the value can be null.
+ * The value can be retrieved by calling the get method with a key that is equal to the original key.
+ * @param keyName the key
+ * @param value the value
+ */
+void NetworkTable::PutBoolean(const char *keyName, bool value)
+{
+ Put(keyName, std::auto_ptr<NetworkTables::Entry>(new NetworkTables::BooleanEntry(value)));
+}
+
+/**
+ * Maps the specified key to the specified value in this table.
+ * Neither the key nor the value can be null.
+ * The value can be retrieved by calling the get method with a key that is equal to the original key.
+ * @param keyName the key
+ * @param value the value
+ */
+void NetworkTable::PutDouble(const char *keyName, double value)
+{
+ Put(keyName, std::auto_ptr<NetworkTables::Entry>(new NetworkTables::DoubleEntry(value)));
+}
+
+/**
+ * Maps the specified key to the specified value in this table.
+ * Neither the key nor the value can be null.
+ * The value can be retrieved by calling the get method with a key that is equal to the original key.
+ * @param keyName the key
+ * @param value the value
+ */
+void NetworkTable::PutString(const char *keyName, const char *value)
+{
+ if (value == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "value");
+ return;
+ }
+ Put(keyName, std::auto_ptr<NetworkTables::Entry>(new NetworkTables::StringEntry(value)));
+}
+
+void NetworkTable::PutString(std::string keyName, std::string value)
+{
+ PutString(keyName.c_str(), value.c_str());
+}
+
+/**
+ * Maps the specified key to the specified value in this table.
+ * Neither the key nor the value can be null.
+ * The value can be retrieved by calling the get method with a key that is equal to the original key.
+ * @param keyName the key
+ * @param value the value
+ */
+void NetworkTable::PutSubTable(const char *keyName, NetworkTable *value)
+{
+ if (value == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "value");
+ return;
+ }
+ Put(keyName, std::auto_ptr<NetworkTables::Entry>(new NetworkTables::TableEntry(value)));
+}
+
+UINT32 NetworkTable::GrabId()
+{
+ Synchronized sync(_staticMemberMutex);
+ return _currentId++;
+}
+
+void NetworkTable::ProcessTransaction(bool confirmed, NetworkTables::NetworkQueue *transaction)
+{
+ if (transaction->IsEmpty())
+ return;
+
+ NetworkTables::Connection *source = ((NetworkTables::Entry *)transaction->Peek())->GetSource();
+
+ Synchronized sync(m_dataLock);
+
+ std::set<NetworkTables::Connection *>::iterator it, end;
+ it = m_connections.begin();
+ end = m_connections.end();
+ for (; it != end; it++)
+ if (*it != source)
+ (*it)->OfferTransaction(transaction);
+
+ while (!transaction->IsEmpty())
+ {
+ std::pair<NetworkTables::Data *, bool> data = transaction->Poll();
+ // TODO: Remove this
+ if (!data.second)
+ printf("Internal error!");
+ std::auto_ptr<NetworkTables::Entry> entry =
+ std::auto_ptr<NetworkTables::Entry>((NetworkTables::Entry *)data.first);
+ std::auto_ptr<NetworkTables::Entry> oldEntry = entry->GetKey()->SetEntry(entry);
+ if (oldEntry.get() == NULL)
+ m_hasAdded->Offer(data.first);
+ else // TODO: Filter unchanged values
+ m_hasChanged->Offer(data.first);
+ }
+ while (!m_hasAdded->IsEmpty())
+ {
+ NetworkTables::Entry *entry = (NetworkTables::Entry *)m_hasAdded->Poll().first;
+ AlertListeners(true, confirmed, entry->GetKey()->GetName().c_str(), entry);
+ }
+ while (!m_hasChanged->IsEmpty())
+ {
+ NetworkTables::Entry *entry = (NetworkTables::Entry *)m_hasChanged->Poll().first;
+ AlertListeners(true, confirmed, entry->GetKey()->GetName().c_str(), entry);
+ }
+}
+
+void NetworkTable::AddConnection(NetworkTables::Connection *connection)
+{
+ Synchronized sync(m_dataLock);
+
+ if (m_connections.insert(connection).second)
+ {
+ DataMap::iterator it = m_data.begin();
+ DataMap::iterator end = m_data.end();
+ for (; it != end; it++)
+ {
+ connection->Offer(it->second);
+ if(it->second->HasEntry())
+ connection->Offer(it->second->GetEntry());
+ }
+ if (m_connections.size() == 1)
+ {
+ Synchronized syncStatic(_staticMemberMutex);
+ _tableIdMap.insert(TableIdMap::value_type(m_id, this));
+
+ std::set<NetworkTableConnectionListener *>::iterator lit, lend;
+ lit = m_connectionListeners.begin();
+ lend = m_connectionListeners.end();
+ for (; lit != lend; lit++)
+ (*lit)->Connected(this);
+ }
+ }
+}
+
+void NetworkTable::RemoveConnection(NetworkTables::Connection *connection)
+{
+ Synchronized sync(m_dataLock);
+
+ m_connections.erase(connection);
+
+ if (m_connections.size() == 0)
+ {
+ Synchronized syncStatic(_staticMemberMutex);
+ _tableIdMap.erase(m_id);
+
+ std::set<NetworkTableConnectionListener *>::iterator lit, lend;
+ lit = m_connectionListeners.begin();
+ lend = m_connectionListeners.end();
+ for (; lit != lend; lit++)
+ (*lit)->Disconnected(this);
+ }
+}
+
+/**
+ * Returns the key that the name maps to. This should
+ * never fail, if their is no key for that name, then one should be made.
+ * @param keyName the name
+ * @return the key
+ */
+NetworkTables::Key *NetworkTable::GetKey(const char *keyName)
+{
+ Synchronized sync(m_dataLock);
+ // Insert will add a new element if the key is not found
+ // or will return the existing key if it is found.
+ std::pair<DataMap::iterator, bool> ret =
+ m_data.insert(DataMap::value_type(keyName, NULL));
+ if (ret.second)
+ {
+ // Key not found. Create a new one.
+ ret.first->second = new NetworkTables::Key(this, keyName);
+ if (m_connections.size() != 0)
+ {
+ std::set<NetworkTables::Connection *>::iterator it, end;
+ it = m_connections.begin();
+ end = m_connections.end();
+ for (; it != end; it++)
+ (*it)->Offer(ret.first->second);
+ }
+ }
+ return ret.first->second;
+}
+
+void NetworkTable::Put(const char *keyName, std::auto_ptr<NetworkTables::Entry> value)
+{
+ if (keyName == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "keyName");
+ return;
+ }
+ Synchronized sync(m_dataLock);
+ NetworkTables::Key *key = GetKey(keyName);
+ value->SetKey(key);
+
+ if (m_transactionCount == 0)
+ Got(true, key, value);
+ else
+ m_transaction->Offer(std::auto_ptr<NetworkTables::Data>(value.release()));
+}
+
+void NetworkTable::Send(NetworkTables::Entry *entry)
+{
+ Synchronized sync(m_dataLock);
+ std::set<NetworkTables::Connection *>::iterator it, end;
+ it = m_connections.begin();
+ end = m_connections.end();
+ for (; it != end; it++)
+ if (*it != entry->GetSource())
+ (*it)->Offer(entry);
+}
+
+/**
+ * This method should be called by children when they want to add a new value.
+ * It will notify listeners of the value
+ * @param confirmed whether or not this value was confirmed or received
+ * @param key the key
+ * @param value the value
+ */
+void NetworkTable::Got(bool confirmed, NetworkTables::Key *key, std::auto_ptr<NetworkTables::Entry> value)
+{
+ std::auto_ptr<NetworkTables::Entry> old;
+ {
+ Synchronized sync(m_dataLock);
+ old = key->SetEntry(value);
+ }
+ // TODO: return if value didn't change
+
+ Send(key->GetEntry());
+ AlertListeners(old.get() == NULL, confirmed, key->GetName().c_str(), key->GetEntry());
+}
+
+void NetworkTable::AlertListeners(bool isNew, bool confirmed, const char *keyName,
+ NetworkTables::Entry *value)
+{
+ Synchronized sync(m_listenerLock);
+
+ if (isNew && m_additionListeners.size() != 0)
+ {
+ std::set<NetworkTableAdditionListener *>::iterator lit, lend;
+ lit = m_additionListeners.begin();
+ lend = m_additionListeners.end();
+ for (; lit != lend; lit++)
+ (*lit)->FieldAdded(this, keyName, value->GetType());
+ }
+
+ ListenersMap::iterator listeners = m_listeners.find(keyName);
+ if (listeners != m_listeners.end())
+ {
+ std::set<NetworkTableChangeListener *>::iterator lit, lend;
+ lit = listeners->second.begin();
+ lend = listeners->second.end();
+ for (; lit != lend; lit++)
+ {
+ if (confirmed)
+ (*lit)->ValueConfirmed(this, keyName, value->GetType());
+ else
+ (*lit)->ValueChanged(this, keyName, value->GetType());
+ }
+ }
+
+ {
+ std::set<NetworkTableChangeListener *>::iterator lit, lend;
+ lit = m_listenToAllListeners.begin();
+ lend = m_listenToAllListeners.end();
+ for (; lit != lend; lit++)
+ {
+ if (confirmed)
+ (*lit)->ValueConfirmed(this, keyName, value->GetType());
+ else
+ (*lit)->ValueChanged(this, keyName, value->GetType());
+ }
+ }
+}
+
+void NetworkTable::EncodeName(NetworkTables::Buffer *buffer)
+{
+ buffer->WriteTableId(m_id);
+}
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/NetworkTable.h b/aos/externals/WPILib/WPILib/NetworkTables/NetworkTable.h
new file mode 100644
index 0000000..df978b8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/NetworkTable.h
@@ -0,0 +1,127 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __NETWORK_TABLE_H__
+#define __NETWORK_TABLE_H__
+
+#include "ErrorBase.h"
+#include <map>
+#include <set>
+#include <vector>
+
+namespace NetworkTables
+{
+ class Buffer;
+ class Connection;
+ class Entry;
+ class Key;
+ class NetworkQueue;
+ class TableAssignment;
+ class TableEntry;
+}
+
+class NetworkTableChangeListener;
+class NetworkTableAdditionListener;
+class NetworkTableConnectionListener;
+
+class NetworkTable : public ErrorBase {
+ friend class NetworkTables::Connection;
+ friend class NetworkTables::Key;
+ friend class NetworkTables::TableAssignment;
+ friend class NetworkTables::TableEntry;
+public:
+ NetworkTable();
+ ~NetworkTable();
+ static void Initialize();
+ static NetworkTable *GetTable(const char *tableName);
+ static NetworkTable *GetTable(int id);
+ std::vector<const char *> GetKeys();
+ void BeginTransaction();
+ void EndTransaction();
+ void AddChangeListener(const char *keyName, NetworkTableChangeListener *listener);
+ void AddChangeListenerAny(NetworkTableChangeListener *listener);
+ void RemoveChangeListener(const char *keyName, NetworkTableChangeListener *listener);
+ void RemoveChangeListenerAny(NetworkTableChangeListener *listener);
+ void AddAdditionListener(NetworkTableAdditionListener *listener);
+ void RemoveAdditionListener(NetworkTableAdditionListener *listener);
+ void AddConnectionListener(NetworkTableConnectionListener *listener, bool immediateNotify);
+ void RemoveConnectionListener(NetworkTableConnectionListener *listener);
+ bool IsConnected();
+ bool ContainsKey(const char *keyName);
+ NetworkTables::Entry *GetEntry(const char *keyName);
+
+ int GetInt(const char *keyName);
+ bool GetBoolean(const char *keyName);
+ double GetDouble(const char *keyName);
+ int GetString(const char *keyName, char *value, int len);
+ std::string GetString(std::string keyName);
+ NetworkTable *GetSubTable(const char *keyName);
+ void PutInt(const char *keyName, int value);
+ void PutBoolean(const char *keyName, bool value);
+ void PutDouble(const char *keyName, double value);
+ void PutString(const char *keyName, const char *value);
+ void PutString(std::string keyName, std::string value);
+ void PutSubTable(const char *keyName, NetworkTable *value);
+
+private:
+ static UINT32 GrabId();
+ void ProcessTransaction(bool confirmed, NetworkTables::NetworkQueue *transaction);
+ UINT32 GetId() {return m_id;}
+ void AddConnection(NetworkTables::Connection *connection);
+ void RemoveConnection(NetworkTables::Connection *connection);
+ NetworkTables::Key *GetKey(const char *keyName);
+ void Put(const char *keyName, std::auto_ptr<NetworkTables::Entry> value);
+ void Send(NetworkTables::Entry *entry);
+ void Got(bool confirmed, NetworkTables::Key *key, std::auto_ptr<NetworkTables::Entry> value);
+ void AlertListeners(bool isNew, bool confirmed, const char *keyName, NetworkTables::Entry *value);
+ void EncodeName(NetworkTables::Buffer *buffer);
+
+ /** The lock for data */
+ SEM_ID m_dataLock;
+ /** The actual data */
+ typedef std::map<std::string, NetworkTables::Key *> DataMap;
+ DataMap m_data;
+ /** The connections this table has */
+ std::set<NetworkTables::Connection *> m_connections;
+ /** The lock for listener modification */
+ SEM_ID m_listenerLock;
+ /** Set of NetworkingListeners who register for everything */
+ std::set<NetworkTableChangeListener *> m_listenToAllListeners;
+ /** Links names to NetworkingListeners */
+ typedef std::map<std::string, std::set<NetworkTableChangeListener *> > ListenersMap;
+ ListenersMap m_listeners;
+ /** Set of addition listeners */
+ std::set<NetworkTableAdditionListener *> m_additionListeners;
+ /** Set of connection listeners */
+ std::set<NetworkTableConnectionListener *> m_connectionListeners;
+ /** The id of this table */
+ UINT32 m_id;
+ /** The queue of the current transaction */
+ NetworkTables::NetworkQueue *m_transaction;
+ /** The number of times begin transaction has been called without a matching end transaction */
+ int m_transactionCount;
+ /** A list of values which need to be signaled */
+ NetworkTables::NetworkQueue *m_hasChanged;
+ /** A list of values which has been added */
+ NetworkTables::NetworkQueue *m_hasAdded;
+
+ /** Links names to tables */
+ typedef std::map<std::string, NetworkTable *> TableNameMap;
+ static TableNameMap _tableNameMap;
+ /** Links ids to currently active NetworkingTables */
+ typedef std::map<UINT32, NetworkTable *> TableIdMap;
+ static TableIdMap _tableIdMap;
+ /** The currently available id */
+ static UINT32 _currentId;
+ /** Indicates that static variables are initialized */
+ static bool _initialized;
+ /** Protects access to static members */
+ static SEM_ID _staticMemberMutex;
+ /** Usage Guidelines... */
+ DISALLOW_COPY_AND_ASSIGN(NetworkTable);
+};
+
+#endif // __NETWORK_TABLE_H__
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/NetworkTableAdditionListener.h b/aos/externals/WPILib/WPILib/NetworkTables/NetworkTableAdditionListener.h
new file mode 100644
index 0000000..b115347
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/NetworkTableAdditionListener.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __NETWORK_TABLE_ADDITION_LISTENER_H__
+#define __NETWORK_TABLE_ADDITION_LISTENER_H__
+
+#include "NetworkTables/InterfaceConstants.h"
+
+class NetworkTable;
+
+class NetworkTableAdditionListener {
+public:
+ virtual void FieldAdded(NetworkTable *table, const char *name, NetworkTables_Types type) = 0;
+};
+
+#endif // __NETWORK_TABLE_ADDITION_LISTENER_H__
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/NetworkTableChangeListener.h b/aos/externals/WPILib/WPILib/NetworkTables/NetworkTableChangeListener.h
new file mode 100644
index 0000000..f5b0265
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/NetworkTableChangeListener.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __NETWORK_TABLE_CHANGE_LISTENER_H__
+#define __NETWORK_TABLE_CHANGE_LISTENER_H__
+
+#include "NetworkTables/InterfaceConstants.h"
+
+class NetworkTable;
+
+class NetworkTableChangeListener {
+public:
+public:
+ virtual void ValueChanged(NetworkTable *table, const char *name, NetworkTables_Types type) = 0;
+ virtual void ValueConfirmed(NetworkTable *table, const char *name, NetworkTables_Types type) = 0;
+};
+
+#endif // __NETWORK_TABLE_CHANGE_LISTENER_H__
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/NetworkTableConnectionListener.h b/aos/externals/WPILib/WPILib/NetworkTables/NetworkTableConnectionListener.h
new file mode 100644
index 0000000..d58c5c1
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/NetworkTableConnectionListener.h
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __NETWORK_TABLE_CONNECTION_LISTENER_H__
+#define __NETWORK_TABLE_CONNECTION_LISTENER_H__
+
+class NetworkTable;
+
+class NetworkTableConnectionListener {
+public:
+ virtual void Connected(NetworkTable *table) = 0;
+ virtual void Disconnected(NetworkTable *table) = 0;
+};
+
+#endif // __NETWORK_TABLE_CONNECTION_LISTENER_H__
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/OldData.cpp b/aos/externals/WPILib/WPILib/NetworkTables/OldData.cpp
new file mode 100644
index 0000000..8d55242
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/OldData.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/OldData.h"
+#include "NetworkTables/Buffer.h"
+#include "NetworkTables/Entry.h"
+
+namespace NetworkTables
+{
+
+OldData::OldData(Entry *entry) :
+ m_entry(entry)
+{
+}
+
+void OldData::Encode(Buffer *buffer)
+{
+ buffer->WriteByte(kNetworkTables_OLD_DATA);
+ m_entry->Encode(buffer);
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/OldData.h b/aos/externals/WPILib/WPILib/NetworkTables/OldData.h
new file mode 100644
index 0000000..e2d13d8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/OldData.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __OLD_DATA_H__
+#define __OLD_DATA_H__
+
+#include "NetworkTables/Data.h"
+#include <vxWorks.h>
+
+namespace NetworkTables
+{
+class Buffer;
+class Entry;
+
+class OldData : public Data
+{
+public:
+ OldData(Entry *entry);
+ virtual void Encode(Buffer *buffer);
+ virtual bool IsOldData() {return true;}
+ Entry *GetEntry() {return m_entry;}
+
+private:
+ Entry *m_entry;
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Reader.cpp b/aos/externals/WPILib/WPILib/NetworkTables/Reader.cpp
new file mode 100644
index 0000000..fdc6a46
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Reader.cpp
@@ -0,0 +1,180 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/Reader.h"
+
+#include "NetworkTables/BooleanEntry.h"
+#include "NetworkTables/Connection.h"
+#include "NetworkTables/DoubleEntry.h"
+#include "NetworkTables/IntegerEntry.h"
+#include "NetworkTables/StringEntry.h"
+#include "WPIErrors.h"
+#include <errnoLib.h>
+#include <selectLib.h>
+#include <sockLib.h>
+#include <usrLib.h>
+
+namespace NetworkTables
+{
+
+Reader::Reader(Connection *connection, int inputStreamFd) :
+ m_connection(connection),
+ m_inputStreamFd(inputStreamFd)
+{
+ m_lastByte = -2;
+}
+
+int Reader::Read()
+{
+ fd_set readFdSet;
+ int retval = ERROR;
+
+ FD_ZERO(&readFdSet);
+ FD_SET(m_inputStreamFd, &readFdSet);
+ if (select(FD_SETSIZE, &readFdSet, NULL, NULL, NULL) != ERROR)
+ {
+ if (FD_ISSET(m_inputStreamFd, &readFdSet))
+ {
+ char readbuf;
+ retval = recv(m_inputStreamFd, &readbuf, 1, 0);
+ m_lastByte = readbuf;
+ if (retval != ERROR && retval > 0)
+ {
+#ifdef DEBUG
+ if (m_lastByte != kNetworkTables_PING)
+ {
+ char pbuf[6];
+ snprintf(pbuf, 6, "I:%02X\n", m_lastByte);
+ printf(pbuf);
+ }
+#endif
+ return m_lastByte;
+ }
+ }
+ }
+ else if (!m_connection->IsConnected())
+ {
+ // The error came from us closing the socket
+ return 0;
+ }
+
+ // TODO: Should we ignore ECONNRESET errors?
+ if (retval == ERROR)
+ {
+ char buf[32] = "";
+ int err = errnoGet();
+ snprintf(buf, 32, "errno=%d", err);
+ wpi_setStaticWPIErrorWithContext(m_connection, NetworkTablesReadError, buf);
+ printErrno(err);
+ }
+ m_connection->Close();
+ return 0;
+}
+
+int Reader::Check(bool useLastValue)
+{
+ return useLastValue ? m_lastByte : Read();
+}
+
+std::string Reader::ReadString()
+{
+ Read();
+ std::string buffer;
+
+ if (m_lastByte == kNetworkTables_BEGIN_STRING)
+ {
+ buffer.reserve(360);
+ buffer.clear();
+ while (Read() != kNetworkTables_END_STRING)
+ buffer.append(1, (char)m_lastByte);
+ }
+ else
+ {
+ int length = m_lastByte;
+ buffer.reserve(length + 1);
+ buffer.clear();
+ for (int i = 0; i < length; i++)
+ buffer[i] = (char)Read();
+ buffer[length] = '\0';
+ }
+
+ return buffer;
+}
+
+int Reader::ReadId(bool useLastValue)
+{
+ return ReadVariableSize(useLastValue, kNetworkTables_ID);
+}
+
+int Reader::ReadTableId(bool useLastValue) {
+ return ReadVariableSize(useLastValue, kNetworkTables_TABLE_ID);
+}
+
+int Reader::ReadVariableSize(bool useLastValue, int tag) {
+ int value = Check(useLastValue);
+ value ^= tag;
+ if (value < tag - 4)
+ {
+ return value;
+ }
+ else
+ {
+ int bytes = (value & 3) + 1;
+ int id = 0;
+ for (int i = 0; i < bytes; i++)
+ id = (id << 8) | Read();
+ return id;
+ }
+}
+
+int Reader::ReadInt()
+{
+ return (Read() << 24) | (Read() << 16) | (Read() << 8) | Read();
+}
+
+double Reader::ReadDouble()
+{
+ long l = Read();
+ l = (l << 8) | Read();
+ l = (l << 8) | Read();
+ l = (l << 8) | Read();
+ l = (l << 8) | Read();
+ l = (l << 8) | Read();
+ l = (l << 8) | Read();
+ l = (l << 8) | Read();
+ return *((double *)&l);
+}
+
+int Reader::ReadConfirmations(bool useLastValue)
+{
+ return Check(useLastValue) ^ kNetworkTables_CONFIRMATION;
+}
+
+int Reader::ReadDenials(bool useLastValue)
+{
+ return Check(useLastValue) ^ kNetworkTables_DENIAL;
+}
+
+std::auto_ptr<Entry> Reader::ReadEntry(bool useLastValue)
+{
+ switch (Check(useLastValue))
+ {
+ case kNetworkTables_BOOLEAN_FALSE:
+ return std::auto_ptr<Entry>(new BooleanEntry(false));
+ case kNetworkTables_BOOLEAN_TRUE:
+ return std::auto_ptr<Entry>(new BooleanEntry(true));
+ case kNetworkTables_INT:
+ return std::auto_ptr<Entry>(new IntegerEntry(ReadInt()));
+ case kNetworkTables_DOUBLE:
+ return std::auto_ptr<Entry>(new DoubleEntry(ReadDouble()));
+ case kNetworkTables_STRING:
+ return std::auto_ptr<Entry>(new StringEntry(ReadString().c_str()));
+ default:
+ return std::auto_ptr<Entry>(NULL);
+ }
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/Reader.h b/aos/externals/WPILib/WPILib/NetworkTables/Reader.h
new file mode 100644
index 0000000..a13eb09
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/Reader.h
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __READER_H__
+#define __READER_H__
+
+#include "NetworkTables/Entry.h"
+#include <memory>
+#include <string>
+
+namespace NetworkTables
+{
+class Connection;
+
+class Reader
+{
+public:
+ Reader(Connection *connection, int inputStreamFd);
+ int Read();
+ std::string ReadString();
+ int ReadId(bool useLastValue);
+ int ReadTableId(bool useLastValue);
+ int ReadInt();
+ double ReadDouble();
+ int ReadConfirmations(bool useLastValue);
+ int ReadDenials(bool useLastValue);
+ std::auto_ptr<Entry> ReadEntry(bool useLastValue);
+private:
+ int Check(bool useLastValue);
+ int ReadVariableSize(bool useLastValue, int tag);
+
+ /** The connection associated with this reader */
+ Connection *m_connection;
+ /** The input stream */
+ int m_inputStreamFd;
+ /** The last read value (-2 if nothing has been read) */
+ int m_lastByte;
+
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/StringEntry.cpp b/aos/externals/WPILib/WPILib/NetworkTables/StringEntry.cpp
new file mode 100644
index 0000000..a8db0cd
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/StringEntry.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/StringEntry.h"
+#include "NetworkTables/Buffer.h"
+
+namespace NetworkTables
+{
+
+StringEntry::StringEntry(const char *str)
+{
+ m_value = str;
+}
+
+NetworkTables_Types StringEntry::GetType()
+{
+ return kNetworkTables_Types_STRING;
+}
+
+void StringEntry::Encode(Buffer *buffer)
+{
+ Entry::Encode(buffer);
+ buffer->WriteByte(kNetworkTables_STRING);
+ buffer->WriteString(m_value.c_str());
+}
+
+int StringEntry::GetString(char *str, int len)
+{
+ return (int)m_value.copy(str, len);
+}
+
+std::string StringEntry::GetString()
+{
+ return m_value;
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/StringEntry.h b/aos/externals/WPILib/WPILib/NetworkTables/StringEntry.h
new file mode 100644
index 0000000..43c65b2
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/StringEntry.h
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __STRING_ENTRY_H__
+#define __STRING_ENTRY_H__
+
+#include "NetworkTables/Entry.h"
+#include "NetworkTables/InterfaceConstants.h"
+#include <vxWorks.h>
+#include <string>
+
+class NetworkTable;
+
+namespace NetworkTables
+{
+
+class Buffer;
+
+class StringEntry : public Entry {
+public:
+ StringEntry(const char *str);
+ virtual ~StringEntry() {}
+ virtual NetworkTables_Types GetType();
+ virtual void Encode(Buffer *buffer);
+ virtual int GetString(char *str, int len);
+ virtual std::string GetString();
+
+private:
+ std::string m_value;
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/TableAssignment.cpp b/aos/externals/WPILib/WPILib/NetworkTables/TableAssignment.cpp
new file mode 100644
index 0000000..1629e9c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/TableAssignment.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/TableAssignment.h"
+#include "NetworkTables/Buffer.h"
+#include "NetworkTables/InterfaceConstants.h"
+#include "NetworkTables/NetworkTable.h"
+
+namespace NetworkTables
+{
+
+TableAssignment::TableAssignment(NetworkTable *table, int alteriorId) :
+ m_table(table),
+ m_alteriorId(alteriorId)
+{
+}
+
+void TableAssignment::Encode(Buffer *buffer)
+{
+ buffer->WriteByte(kNetworkTables_TABLE_ASSIGNMENT);
+ buffer->WriteTableId(m_alteriorId);
+ m_table->EncodeName(buffer);
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/TableAssignment.h b/aos/externals/WPILib/WPILib/NetworkTables/TableAssignment.h
new file mode 100644
index 0000000..b8fa029
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/TableAssignment.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __TABLE_ASSIGNMENT_H__
+#define __TABLE_ASSIGNMENT_H__
+
+#include "NetworkTables/Data.h"
+
+class NetworkTable;
+
+namespace NetworkTables
+{
+
+class Buffer;
+
+class TableAssignment : public Data
+{
+public:
+ TableAssignment(NetworkTable *table, int alteriorId);
+ virtual void Encode(Buffer *buffer);
+
+private:
+ NetworkTable *m_table;
+ int m_alteriorId;
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/TableEntry.cpp b/aos/externals/WPILib/WPILib/NetworkTables/TableEntry.cpp
new file mode 100644
index 0000000..b14add8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/TableEntry.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/TableEntry.h"
+#include "NetworkTables/InterfaceConstants.h"
+#include "NetworkTables/NetworkTable.h"
+
+namespace NetworkTables
+{
+
+TableEntry::TableEntry(NetworkTable *value) :
+ m_value(value)
+{
+}
+
+NetworkTables_Types TableEntry::GetType()
+{
+ return kNetworkTables_Types_TABLE;
+}
+
+void TableEntry::Encode(Buffer *buffer)
+{
+ Entry::Encode(buffer);
+ m_value->EncodeName(buffer);
+}
+
+NetworkTable *TableEntry::GetTable()
+{
+ return m_value;
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/TableEntry.h b/aos/externals/WPILib/WPILib/NetworkTables/TableEntry.h
new file mode 100644
index 0000000..0e8032c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/TableEntry.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __TABLE_ENTRY_H__
+#define __TABLE_ENTRY_H__
+
+#include "NetworkTables/Entry.h"
+#include <vxWorks.h>
+
+class NetworkTable;
+
+namespace NetworkTables
+{
+class Buffer;
+
+class TableEntry : public Entry
+{
+public:
+ TableEntry(NetworkTable *value);
+ virtual NetworkTables_Types GetType();
+ virtual void Encode(Buffer *buffer);
+ virtual NetworkTable *GetTable();
+
+private:
+ NetworkTable *m_value;
+};
+
+} // namespace
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/TransactionEnd.cpp b/aos/externals/WPILib/WPILib/NetworkTables/TransactionEnd.cpp
new file mode 100644
index 0000000..8b046a2
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/TransactionEnd.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/TransactionEnd.h"
+#include "NetworkTables/Buffer.h"
+#include "NetworkTables/InterfaceConstants.h"
+
+namespace NetworkTables
+{
+
+void TransactionEnd::Encode(Buffer *buffer)
+{
+ buffer->WriteByte(kNetworkTables_TRANSACTION);
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/TransactionEnd.h b/aos/externals/WPILib/WPILib/NetworkTables/TransactionEnd.h
new file mode 100644
index 0000000..a7281b6
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/TransactionEnd.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __TRANSACTION_END_H__
+#define __TRANSACTION_END_H__
+
+#include "NetworkTables/Data.h"
+
+namespace NetworkTables
+{
+class Buffer;
+
+class TransactionEnd : public Data
+{
+public:
+ virtual void Encode(Buffer *buffer);
+ virtual bool IsTransaction() {return true;}
+};
+
+} // namespace
+
+#endif // __TRANSACTION_END_H__
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/TransactionStart.cpp b/aos/externals/WPILib/WPILib/NetworkTables/TransactionStart.cpp
new file mode 100644
index 0000000..33d564e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/TransactionStart.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "NetworkTables/TransactionStart.h"
+#include "NetworkTables/Buffer.h"
+#include "NetworkTables/InterfaceConstants.h"
+
+namespace NetworkTables
+{
+
+void TransactionStart::Encode(Buffer *buffer)
+{
+ buffer->WriteByte(kNetworkTables_TRANSACTION);
+}
+
+} // namespace
diff --git a/aos/externals/WPILib/WPILib/NetworkTables/TransactionStart.h b/aos/externals/WPILib/WPILib/NetworkTables/TransactionStart.h
new file mode 100644
index 0000000..245c93c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/NetworkTables/TransactionStart.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __TRANSACTION_START_H__
+#define __TRANSACTION_START_H__
+
+#include "NetworkTables/Data.h"
+
+namespace NetworkTables
+{
+
+class Buffer;
+
+class TransactionStart : public Data
+{
+public:
+ virtual void Encode(Buffer *buffer);
+ virtual bool IsTransaction() {return true;}
+};
+
+} // namespace
+
+#endif // __TRANSACTION_START_H__
diff --git a/aos/externals/WPILib/WPILib/Notifier.cpp b/aos/externals/WPILib/WPILib/Notifier.cpp
new file mode 100644
index 0000000..bafae85
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Notifier.cpp
@@ -0,0 +1,273 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Notifier.h"
+#include "Timer.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+const UINT32 Notifier::kTimerInterruptNumber;
+Notifier *Notifier::timerQueueHead = NULL;
+Semaphore Notifier::queueSemaphore;
+tAlarm *Notifier::talarm = NULL;
+tInterruptManager *Notifier::manager = NULL;
+int Notifier::refcount = 0;
+
+/**
+ * Create a Notifier for timer event notification.
+ * @param handler The handler is called at the notification time which is set
+ * using StartSingle or StartPeriodic.
+ */
+Notifier::Notifier(TimerEventHandler handler, void *param)
+{
+ if (handler == NULL)
+ wpi_setWPIErrorWithContext(NullParameter, "handler must not be NULL");
+ m_handler = handler;
+ m_param = param;
+ m_periodic = false;
+ m_expirationTime = 0;
+ m_period = 0;
+ m_nextEvent = NULL;
+ m_queued = false;
+ m_handlerSemaphore = semBCreate(SEM_Q_PRIORITY, SEM_FULL);
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ {
+ Synchronized sync(queueSemaphore);
+ // do the first time intialization of static variables
+ if (refcount == 0)
+ {
+ manager = new tInterruptManager(1 << kTimerInterruptNumber, false, &localStatus);
+ manager->registerHandler(ProcessQueue, NULL, &localStatus);
+ manager->enable(&localStatus);
+ talarm = tAlarm::create(&localStatus);
+ }
+ refcount++;
+ }
+ wpi_setError(localStatus);
+}
+
+/**
+ * Free the resources for a timer event.
+ * All resources will be freed and the timer event will be removed from the
+ * queue if necessary.
+ */
+Notifier::~Notifier()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ {
+ Synchronized sync(queueSemaphore);
+ DeleteFromQueue();
+
+ // Delete the static variables when the last one is going away
+ if (!(--refcount))
+ {
+ talarm->writeEnable(false, &localStatus);
+ delete talarm;
+ talarm = NULL;
+ manager->disable(&localStatus);
+ delete manager;
+ manager = NULL;
+ }
+ }
+ wpi_setError(localStatus);
+
+ // Acquire the semaphore; this makes certain that the handler is
+ // not being executed by the interrupt manager.
+ semTake(m_handlerSemaphore, WAIT_FOREVER);
+ // Delete while holding the semaphore so there can be no race.
+ semDelete(m_handlerSemaphore);
+}
+
+/**
+ * Update the alarm hardware to reflect the current first element in the queue.
+ * Compute the time the next alarm should occur based on the current time and the
+ * period for the first element in the timer queue.
+ * WARNING: this method does not do synchronization! It must be called from somewhere
+ * that is taking care of synchronizing access to the queue.
+ */
+void Notifier::UpdateAlarm()
+{
+ if (timerQueueHead != NULL)
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ // write the first item in the queue into the trigger time
+ talarm->writeTriggerTime((UINT32)(timerQueueHead->m_expirationTime * 1e6), &localStatus);
+ // Enable the alarm. The hardware disables itself after each alarm.
+ talarm->writeEnable(true, &localStatus);
+ wpi_setStaticError(timerQueueHead, localStatus);
+ }
+}
+
+/**
+ * ProcessQueue is called whenever there is a timer interrupt.
+ * We need to wake up and process the current top item in the timer queue as long
+ * as its scheduled time is after the current time. Then the item is removed or
+ * rescheduled (repetitive events) in the queue.
+ */
+void Notifier::ProcessQueue(uint32_t mask, void *params)
+{
+ Notifier *current;
+ while (true) // keep processing past events until no more
+ {
+ {
+ Synchronized sync(queueSemaphore);
+ double currentTime = GetClock();
+ current = timerQueueHead;
+ if (current == NULL || current->m_expirationTime > currentTime)
+ {
+ break; // no more timer events to process
+ }
+ // need to process this entry
+ timerQueueHead = current->m_nextEvent;
+ if (current->m_periodic)
+ {
+ // if periodic, requeue the event
+ // compute when to put into queue
+ current->InsertInQueue(true);
+ }
+ else
+ {
+ // not periodic; removed from queue
+ current->m_queued = false;
+ }
+ // Take handler semaphore while holding queue semaphore to make sure
+ // the handler will execute to completion in case we are being deleted.
+ semTake(current->m_handlerSemaphore, WAIT_FOREVER);
+ }
+
+ current->m_handler(current->m_param); // call the event handler
+ semGive(current->m_handlerSemaphore);
+ }
+ // reschedule the first item in the queue
+ Synchronized sync(queueSemaphore);
+ UpdateAlarm();
+}
+
+/**
+ * Insert this Notifier into the timer queue in right place.
+ * WARNING: this method does not do synchronization! It must be called from somewhere
+ * that is taking care of synchronizing access to the queue.
+ * @param reschedule If false, the scheduled alarm is based on the curent time and UpdateAlarm
+ * method is called which will enable the alarm if necessary.
+ * If true, update the time by adding the period (no drift) when rescheduled periodic from ProcessQueue.
+ * This ensures that the public methods only update the queue after finishing inserting.
+ */
+void Notifier::InsertInQueue(bool reschedule)
+{
+ if (reschedule)
+ {
+ m_expirationTime += m_period;
+ }
+ else
+ {
+ m_expirationTime = GetClock() + m_period;
+ }
+ if (timerQueueHead == NULL || timerQueueHead->m_expirationTime >= this->m_expirationTime)
+ {
+ // the queue is empty or greater than the new entry
+ // the new entry becomes the first element
+ this->m_nextEvent = timerQueueHead;
+ timerQueueHead = this;
+ if (!reschedule)
+ {
+ // since the first element changed, update alarm, unless we already plan to
+ UpdateAlarm();
+ }
+ }
+ else
+ {
+ for (Notifier **npp = &(timerQueueHead->m_nextEvent); ; npp = &(*npp)->m_nextEvent)
+ {
+ Notifier *n = *npp;
+ if (n == NULL || n->m_expirationTime > this->m_expirationTime)
+ {
+ *npp = this;
+ this->m_nextEvent = n;
+ break;
+ }
+ }
+ }
+ m_queued = true;
+}
+
+/**
+ * Delete this Notifier from the timer queue.
+ * WARNING: this method does not do synchronization! It must be called from somewhere
+ * that is taking care of synchronizing access to the queue.
+ * Remove this Notifier from the timer queue and adjust the next interrupt time to reflect
+ * the current top of the queue.
+ */
+void Notifier::DeleteFromQueue()
+{
+ if (m_queued)
+ {
+ m_queued = false;
+ wpi_assert(timerQueueHead != NULL);
+ if (timerQueueHead == this)
+ {
+ // remove the first item in the list - update the alarm
+ timerQueueHead = this->m_nextEvent;
+ UpdateAlarm();
+ }
+ else
+ {
+ for (Notifier *n = timerQueueHead; n != NULL; n = n->m_nextEvent)
+ {
+ if (n->m_nextEvent == this)
+ {
+ // this element is the next element from *n from the queue
+ n->m_nextEvent = this->m_nextEvent; // point around this one
+ }
+ }
+ }
+ }
+}
+
+/**
+ * Register for single event notification.
+ * A timer event is queued for a single event after the specified delay.
+ * @param delay Seconds to wait before the handler is called.
+ */
+void Notifier::StartSingle(double delay)
+{
+ Synchronized sync(queueSemaphore);
+ m_periodic = false;
+ m_period = delay;
+ DeleteFromQueue();
+ InsertInQueue(false);
+}
+
+/**
+ * Register for periodic event notification.
+ * A timer event is queued for periodic event notification. Each time the interrupt
+ * occurs, the event will be immedeatly requeued for the same time interval.
+ * @param period Period in seconds to call the handler starting one period after the call to this method.
+ */
+void Notifier::StartPeriodic(double period)
+{
+ Synchronized sync(queueSemaphore);
+ m_periodic = true;
+ m_period = period;
+ DeleteFromQueue();
+ InsertInQueue(false);
+}
+
+/**
+ * Stop timer events from occuring.
+ * Stop any repeating timer events from occuring. This will also remove any single
+ * notification events from the queue.
+ * If a timer-based call to the registered handler is in progress, this function will
+ * block until the handler call is complete.
+ */
+void Notifier::Stop()
+{
+ {
+ Synchronized sync(queueSemaphore);
+ DeleteFromQueue();
+ }
+ // Wait for a currently executing handler to complete before returning from Stop()
+ Synchronized sync(m_handlerSemaphore);
+}
diff --git a/aos/externals/WPILib/WPILib/Notifier.h b/aos/externals/WPILib/WPILib/Notifier.h
new file mode 100644
index 0000000..5bcfc92
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Notifier.h
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NOTIFIER_H
+#define NOTIFIER_H
+
+#include "ChipObject.h"
+#include "ErrorBase.h"
+#include "Synchronized.h"
+
+typedef void (*TimerEventHandler)(void *param);
+
+class Notifier : public ErrorBase
+{
+public:
+ Notifier(TimerEventHandler handler, void *param = NULL);
+ virtual ~Notifier();
+ void StartSingle(double delay);
+ void StartPeriodic(double period);
+ void Stop();
+private:
+ static Notifier *timerQueueHead;
+ static Semaphore queueSemaphore;
+ static tAlarm *talarm;
+ static tInterruptManager *manager;
+ static int refcount;
+
+ static const UINT32 kTimerInterruptNumber = 28;
+ static void ProcessQueue(uint32_t mask, void *params); // process the timer queue on a timer event
+ static void UpdateAlarm(); // update the FPGA alarm since the queue has changed
+ void InsertInQueue(bool reschedule); // insert this Notifier in the timer queue
+ void DeleteFromQueue(); // delete this Notifier from the timer queue
+ TimerEventHandler m_handler; // address of the handler
+ void *m_param; // a parameter to pass to the handler
+ double m_period; // the relative time (either periodic or single)
+ double m_expirationTime; // absolute expiration time for the current event
+ Notifier *m_nextEvent; // next Nofifier event
+ bool m_periodic; // true if this is a periodic event
+ bool m_queued; // indicates if this entry is queued
+ SEM_ID m_handlerSemaphore; // held by interrupt manager task while handler call is in progress
+ DISALLOW_COPY_AND_ASSIGN(Notifier);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/PIDController.cpp b/aos/externals/WPILib/WPILib/PIDController.cpp
new file mode 100644
index 0000000..99b7e44
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/PIDController.cpp
@@ -0,0 +1,417 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "PIDController.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Notifier.h"
+#include "PIDSource.h"
+#include "PIDOutput.h"
+#include <math.h>
+#include "Synchronized.h"
+/**
+ * Allocate a PID object with the given constants for P, I, D
+ * @param Kp the proportional coefficient
+ * @param Ki the integral coefficient
+ * @param Kd the derivative coefficient
+ * @param source The PIDSource object that is used to get values
+ * @param output The PIDOutput object that is set to the output value
+ * @param period the loop time for doing calculations. This particularly effects calculations of the
+ * integral and differental terms. The default is 50ms.
+ */
+PIDController::PIDController(float Kp, float Ki, float Kd,
+ PIDSource *source, PIDOutput *output,
+ float period) :
+ m_semaphore (0)
+{
+ m_semaphore = semBCreate(SEM_Q_PRIORITY, SEM_FULL);
+
+ m_controlLoop = new Notifier(PIDController::CallCalculate, this);
+
+ m_P = Kp;
+ m_I = Ki;
+ m_D = Kd;
+ m_maximumOutput = 1.0;
+ m_minimumOutput = -1.0;
+
+ m_maximumInput = 0;
+ m_minimumInput = 0;
+
+ m_continuous = false;
+ m_enabled = false;
+ m_setpoint = 0;
+
+ m_prevError = 0;
+ m_totalError = 0;
+ m_tolerance = .05;
+
+ m_result = 0;
+
+ m_pidInput = source;
+ m_pidOutput = output;
+ m_period = period;
+
+ m_controlLoop->StartPeriodic(m_period);
+
+ static INT32 instances = 0;
+ instances++;
+ nUsageReporting::report(nUsageReporting::kResourceType_PIDController, instances);
+}
+
+/**
+ * Free the PID object
+ */
+PIDController::~PIDController()
+{
+ semFlush(m_semaphore);
+ delete m_controlLoop;
+}
+
+/**
+ * Call the Calculate method as a non-static method. This avoids having to prepend
+ * all local variables in that method with the class pointer. This way the "this"
+ * pointer will be set up and class variables can be called more easily.
+ * This method is static and called by the Notifier class.
+ * @param controller the address of the PID controller object to use in the background loop
+ */
+void PIDController::CallCalculate(void *controller)
+{
+ PIDController *control = (PIDController*) controller;
+ control->Calculate();
+}
+
+ /**
+ * Read the input, calculate the output accordingly, and write to the output.
+ * This should only be called by the Notifier indirectly through CallCalculate
+ * and is created during initialization.
+ */
+void PIDController::Calculate()
+{
+ bool enabled;
+ PIDSource *pidInput;
+
+ CRITICAL_REGION(m_semaphore)
+ {
+ if (m_pidInput == 0) return;
+ if (m_pidOutput == 0) return;
+ enabled = m_enabled;
+ pidInput = m_pidInput;
+ }
+ END_REGION;
+
+ if (enabled)
+ {
+ float input = pidInput->PIDGet();
+ float result;
+ PIDOutput *pidOutput;
+
+ {
+ Synchronized sync(m_semaphore);
+ m_error = m_setpoint - input;
+ if (m_continuous)
+ {
+ if (fabs(m_error) > (m_maximumInput - m_minimumInput) / 2)
+ {
+ if (m_error > 0)
+ {
+ m_error = m_error - m_maximumInput + m_minimumInput;
+ }
+ else
+ {
+ m_error = m_error + m_maximumInput - m_minimumInput;
+ }
+ }
+ }
+
+ double potentialIGain = (m_totalError + m_error) * m_I;
+ if (potentialIGain < m_maximumOutput)
+ {
+ if (potentialIGain > m_minimumOutput)
+ m_totalError += m_error;
+ else
+ m_totalError = m_minimumOutput / m_I;
+ }
+ else
+ {
+ m_totalError = m_maximumOutput / m_I;
+ }
+
+ m_result = m_P * m_error + m_I * m_totalError + m_D * (m_error - m_prevError);
+ m_prevError = m_error;
+
+ if (m_result > m_maximumOutput) m_result = m_maximumOutput;
+ else if (m_result < m_minimumOutput) m_result = m_minimumOutput;
+
+ pidOutput = m_pidOutput;
+ result = m_result;
+ }
+
+ pidOutput->PIDWrite(result);
+ }
+}
+
+/**
+ * Set the PID Controller gain parameters.
+ * Set the proportional, integral, and differential coefficients.
+ * @param p Proportional coefficient
+ * @param i Integral coefficient
+ * @param d Differential coefficient
+ */
+void PIDController::SetPID(float p, float i, float d)
+{
+ CRITICAL_REGION(m_semaphore)
+ {
+ m_P = p;
+ m_I = i;
+ m_D = d;
+ }
+ END_REGION;
+}
+
+/**
+ * Get the Proportional coefficient
+ * @return proportional coefficient
+ */
+float PIDController::GetP()
+{
+ CRITICAL_REGION(m_semaphore)
+ {
+ return m_P;
+ }
+ END_REGION;
+}
+
+/**
+ * Get the Integral coefficient
+ * @return integral coefficient
+ */
+float PIDController::GetI()
+{
+ CRITICAL_REGION(m_semaphore)
+ {
+ return m_I;
+ }
+ END_REGION;
+}
+
+/**
+ * Get the Differential coefficient
+ * @return differential coefficient
+ */
+float PIDController::GetD()
+{
+ CRITICAL_REGION(m_semaphore)
+ {
+ return m_D;
+ }
+ END_REGION;
+}
+
+/**
+ * Return the current PID result
+ * This is always centered on zero and constrained the the max and min outs
+ * @return the latest calculated output
+ */
+float PIDController::Get()
+{
+ float result;
+ CRITICAL_REGION(m_semaphore)
+ {
+ result = m_result;
+ }
+ END_REGION;
+ return result;
+}
+
+/**
+ * Set the PID controller to consider the input to be continuous,
+ * Rather then using the max and min in as constraints, it considers them to
+ * be the same point and automatically calculates the shortest route to
+ * the setpoint.
+ * @param continuous Set to true turns on continuous, false turns off continuous
+ */
+void PIDController::SetContinuous(bool continuous)
+{
+ CRITICAL_REGION(m_semaphore)
+ {
+ m_continuous = continuous;
+ }
+ END_REGION;
+
+}
+
+/**
+ * Sets the maximum and minimum values expected from the input.
+ *
+ * @param minimumInput the minimum value expected from the input
+ * @param maximumInput the maximum value expected from the output
+ */
+void PIDController::SetInputRange(float minimumInput, float maximumInput)
+{
+ CRITICAL_REGION(m_semaphore)
+ {
+ m_minimumInput = minimumInput;
+ m_maximumInput = maximumInput;
+ }
+ END_REGION;
+
+ SetSetpoint(m_setpoint);
+}
+
+/**
+ * Sets the minimum and maximum values to write.
+ *
+ * @param minimumOutput the minimum value to write to the output
+ * @param maximumOutput the maximum value to write to the output
+ */
+void PIDController::SetOutputRange(float minimumOutput, float maximumOutput)
+{
+ CRITICAL_REGION(m_semaphore)
+ {
+ m_minimumOutput = minimumOutput;
+ m_maximumOutput = maximumOutput;
+ }
+ END_REGION;
+}
+
+/**
+ * Set the setpoint for the PIDController
+ * @param setpoint the desired setpoint
+ */
+void PIDController::SetSetpoint(float setpoint)
+{
+ CRITICAL_REGION(m_semaphore)
+ {
+ if (m_maximumInput > m_minimumInput)
+ {
+ if (setpoint > m_maximumInput)
+ m_setpoint = m_maximumInput;
+ else if (setpoint < m_minimumInput)
+ m_setpoint = m_minimumInput;
+ else
+ m_setpoint = setpoint;
+ }
+ else
+ {
+ m_setpoint = setpoint;
+ }
+ }
+ END_REGION;
+}
+
+/**
+ * Returns the current setpoint of the PIDController
+ * @return the current setpoint
+ */
+float PIDController::GetSetpoint()
+{
+ float setpoint;
+ CRITICAL_REGION(m_semaphore)
+ {
+ setpoint = m_setpoint;
+ }
+ END_REGION;
+ return setpoint;
+}
+
+/**
+ * Retruns the current difference of the input from the setpoint
+ * @return the current error
+ */
+float PIDController::GetError()
+{
+ float error;
+ CRITICAL_REGION(m_semaphore)
+ {
+ error = m_error;
+ }
+ END_REGION;
+ return error;
+}
+
+/*
+ * Set the percentage error which is considered tolerable for use with
+ * OnTarget.
+ * @param percentage error which is tolerable
+ */
+void PIDController::SetTolerance(float percent)
+{
+ CRITICAL_REGION(m_semaphore)
+ {
+ m_tolerance = percent;
+ }
+ END_REGION;
+}
+
+/*
+ * Return true if the error is within the percentage of the total input range,
+ * determined by SetTolerance. This asssumes that the maximum and minimum input
+ * were set using SetInput.
+ */
+bool PIDController::OnTarget()
+{
+ bool temp;
+ CRITICAL_REGION(m_semaphore)
+ {
+ temp = fabs(m_error) < (m_tolerance / 100 *
+ (m_maximumInput - m_minimumInput));
+ }
+ END_REGION;
+ return temp;
+}
+
+/**
+ * Begin running the PIDController
+ */
+void PIDController::Enable()
+{
+ CRITICAL_REGION(m_semaphore)
+ {
+ m_enabled = true;
+ }
+ END_REGION;
+}
+/**
+ * Stop running the PIDController, this sets the output to zero before stopping.
+ */
+void PIDController::Disable()
+{
+ CRITICAL_REGION(m_semaphore)
+ {
+ m_pidOutput->PIDWrite(0);
+ m_enabled = false;
+ }
+ END_REGION;
+}
+
+/**
+ * Return true if PIDController is enabled.
+ */
+bool PIDController::IsEnabled()
+{
+ bool enabled;
+ CRITICAL_REGION(m_semaphore)
+ {
+ enabled = m_enabled;
+ }
+ END_REGION;
+ return enabled;
+}
+
+/**
+ * Reset the previous error,, the integral term, and disable the controller.
+ */
+void PIDController::Reset()
+{
+ Disable();
+
+ CRITICAL_REGION(m_semaphore)
+ {
+ m_prevError = 0;
+ m_totalError = 0;
+ m_result = 0;
+ }
+ END_REGION;
+}
diff --git a/aos/externals/WPILib/WPILib/PIDController.h b/aos/externals/WPILib/WPILib/PIDController.h
new file mode 100644
index 0000000..5956f5f
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/PIDController.h
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef PIDCONTROLLER_H_
+#define PIDCONTROLLER_H_
+
+#include "Base.h"
+#include "semLib.h"
+
+class PIDOutput;
+class PIDSource;
+class Notifier;
+
+/**
+ * Class implements a PID Control Loop.
+ *
+ * Creates a separate thread which reads the given PIDSource and takes
+ * care of the integral calculations, as well as writing the given
+ * PIDOutput
+ */
+class PIDController
+{
+public:
+ PIDController(float p, float i, float d,
+ PIDSource *source, PIDOutput *output,
+ float period = 0.05);
+ virtual ~PIDController();
+ virtual float Get();
+ virtual void SetContinuous(bool continuous = true);
+ virtual void SetInputRange(float minimumInput, float maximumInput);
+ virtual void SetOutputRange(float mimimumOutput, float maximumOutput);
+ virtual void SetPID(float p, float i, float d);
+ virtual float GetP();
+ virtual float GetI();
+ virtual float GetD();
+
+ virtual void SetSetpoint(float setpoint);
+ virtual float GetSetpoint();
+
+ virtual float GetError();
+
+ virtual void SetTolerance(float percent);
+ virtual bool OnTarget();
+
+ virtual void Enable();
+ virtual void Disable();
+ virtual bool IsEnabled();
+
+ virtual void Reset();
+
+private:
+ float m_P; // factor for "proportional" control
+ float m_I; // factor for "integral" control
+ float m_D; // factor for "derivative" control
+ float m_maximumOutput; // |maximum output|
+ float m_minimumOutput; // |minimum output|
+ float m_maximumInput; // maximum input - limit setpoint to this
+ float m_minimumInput; // minimum input - limit setpoint to this
+ bool m_continuous; // do the endpoints wrap around? eg. Absolute encoder
+ bool m_enabled; //is the pid controller enabled
+ float m_prevError; // the prior sensor input (used to compute velocity)
+ double m_totalError; //the sum of the errors for use in the integral calc
+ float m_tolerance; //the percetage error that is considered on target
+ float m_setpoint;
+ float m_error;
+ float m_result;
+ float m_period;
+
+ SEM_ID m_semaphore;
+
+ PIDSource *m_pidInput;
+ PIDOutput *m_pidOutput;
+ Notifier *m_controlLoop;
+
+ static void CallCalculate(void *controller);
+ void Calculate();
+ DISALLOW_COPY_AND_ASSIGN(PIDController);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/PIDOutput.h b/aos/externals/WPILib/WPILib/PIDOutput.h
new file mode 100644
index 0000000..81483a6
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/PIDOutput.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef PID_OUTPUT_H
+#define PID_OUTPUT_H
+
+#include "Base.h"
+
+/**
+ * PIDOutput interface is a generic output for the PID class.
+ * PWMs use this class.
+ * Users implement this interface to allow for a PIDController to
+ * read directly from the inputs
+ */
+class PIDOutput
+{
+public:
+ virtual void PIDWrite(float output) = 0;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/PIDSource.h b/aos/externals/WPILib/WPILib/PIDSource.h
new file mode 100644
index 0000000..4f2a209
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/PIDSource.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef PID_SOURCE_H
+#define PID_SOURCE_H
+
+/**
+ * PIDSource interface is a generic sensor source for the PID class.
+ * All sensors that can be used with the PID class will implement the PIDSource that
+ * returns a standard value that will be used in the PID code.
+ */
+class PIDSource
+{
+public:
+ virtual double PIDGet() = 0;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/PPC603gnu/Makefile b/aos/externals/WPILib/WPILib/PPC603gnu/Makefile
new file mode 100644
index 0000000..882fa4e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/PPC603gnu/Makefile
@@ -0,0 +1,1034 @@
+# Wind River Workbench generated Makefile.
+# Do not edit!!!
+#
+# The file ".wrmakefile" is the template used by the Wind River Workbench to
+# generate the makefiles of this project. Add user-specific build targets and
+# make rules only(!) in this project's ".wrmakefile" file. These will then be
+# automatically dumped into the makefiles.
+
+WIND_HOME := $(subst \,/,$(WIND_HOME))
+WIND_BASE := $(subst \,/,$(WIND_BASE))
+WIND_USR := $(subst \,/,$(WIND_USR))
+
+all : pre_build main_all post_build
+
+_clean ::
+ @echo "make: removing targets and objects of `pwd`"
+
+TRACE=0
+TRACEON=$(TRACE:0=@)
+TRACE_FLAG=$(TRACEON:1=)
+
+MAKEFILE := Makefile
+
+FLEXIBLE_BUILD := 1
+
+BUILD_SPEC = PPC603gnu
+DEBUG_MODE = 1
+ifeq ($(DEBUG_MODE),1)
+MODE_DIR := Debug
+else
+MODE_DIR := NonDebug
+endif
+OBJ_DIR := .
+WS_ROOT_DIR := C:/WindRiver/workspace
+PRJ_ROOT_DIR := $(WS_ROOT_DIR)/WPILib
+
+
+
+#Global Build Macros
+PROJECT_TYPE = DKM
+DEFINES =
+EXPAND_DBG = 0
+
+
+#BuildSpec specific Build Macros
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=603 -mstrict-align -mno-implicit-fp -mlongcall
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I.. -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+
+IDE_DEFINES =
+
+
+
+#BuildTool flags
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+DEBUGFLAGS_C++-Compiler = -g
+DEBUGFLAGS_Linker = -g
+DEBUGFLAGS_Partial-Image-Linker =
+DEBUGFLAGS_Librarian =
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+DEBUGFLAGS_Linker = -O2 -fstrength-reduce -fno-builtin
+DEBUGFLAGS_Partial-Image-Linker =
+DEBUGFLAGS_Librarian =
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+
+
+#Project Targets
+PROJECT_TARGETS = WPILib/$(MODE_DIR)/WPILib.a \
+ JavaCameraLib/$(MODE_DIR)/JavaCameraLib.a
+
+
+#Rules
+
+# WPILib
+ifeq ($(DEBUG_MODE),1)
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_C-Compiler = -g
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_C++-Compiler = -g
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_Linker = -g
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_Partial-Image-Linker =
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_Librarian =
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_Assembler = -g
+else
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_Linker = -O2 -fstrength-reduce -fno-builtin
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_Partial-Image-Linker =
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_Librarian =
+WPILib/$(MODE_DIR)/% : DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+WPILib/$(MODE_DIR)/% : IDE_INCLUDES = -I.. -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+WPILib/$(MODE_DIR)/% : IDE_LIBRARIES =
+WPILib/$(MODE_DIR)/% : IDE_DEFINES =
+WPILib/$(MODE_DIR)/% : PROJECT_TYPE = DKM
+WPILib/$(MODE_DIR)/% : DEFINES =
+WPILib/$(MODE_DIR)/% : EXPAND_DBG = 0
+WPILib/$(MODE_DIR)/% : VX_CPU_FAMILY = ppc
+WPILib/$(MODE_DIR)/% : CPU = PPC603
+WPILib/$(MODE_DIR)/% : TOOL_FAMILY = gnu
+WPILib/$(MODE_DIR)/% : TOOL = gnu
+WPILib/$(MODE_DIR)/% : TOOL_PATH =
+WPILib/$(MODE_DIR)/% : CC_ARCH_SPEC = -mcpu=603 -mstrict-align -mno-implicit-fp -mlongcall
+WPILib/$(MODE_DIR)/% : LIBPATH =
+WPILib/$(MODE_DIR)/% : LIBS =
+WPILib/$(MODE_DIR)/% : OBJ_DIR := WPILib/$(MODE_DIR)
+
+WPILib/$(MODE_DIR)/Objects/WPILib/ADXL345_I2C.o : $(PRJ_ROOT_DIR)/ADXL345_I2C.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/ADXL345_SPI.o : $(PRJ_ROOT_DIR)/ADXL345_SPI.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Accelerometer.o : $(PRJ_ROOT_DIR)/Accelerometer.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/AnalogChannel.o : $(PRJ_ROOT_DIR)/AnalogChannel.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/AnalogModule.o : $(PRJ_ROOT_DIR)/AnalogModule.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/AnalogTrigger.o : $(PRJ_ROOT_DIR)/AnalogTrigger.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/AnalogTriggerOutput.o : $(PRJ_ROOT_DIR)/AnalogTriggerOutput.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/AnalogIOButton.o : $(PRJ_ROOT_DIR)/Buttons/AnalogIOButton.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/Button.o : $(PRJ_ROOT_DIR)/Buttons/Button.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/ButtonScheduler.o : $(PRJ_ROOT_DIR)/Buttons/ButtonScheduler.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/DigitalIOButton.o : $(PRJ_ROOT_DIR)/Buttons/DigitalIOButton.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/HeldButtonScheduler.o : $(PRJ_ROOT_DIR)/Buttons/HeldButtonScheduler.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/InternalButton.o : $(PRJ_ROOT_DIR)/Buttons/InternalButton.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/JoystickButton.o : $(PRJ_ROOT_DIR)/Buttons/JoystickButton.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/NetworkButton.o : $(PRJ_ROOT_DIR)/Buttons/NetworkButton.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/PressedButtonScheduler.o : $(PRJ_ROOT_DIR)/Buttons/PressedButtonScheduler.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/ReleasedButtonScheduler.o : $(PRJ_ROOT_DIR)/Buttons/ReleasedButtonScheduler.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CANJaguar.o : $(PRJ_ROOT_DIR)/CANJaguar.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CAccelerometer.o : $(PRJ_ROOT_DIR)/CInterfaces/CAccelerometer.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CAnalogChannel.o : $(PRJ_ROOT_DIR)/CInterfaces/CAnalogChannel.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CCompressor.o : $(PRJ_ROOT_DIR)/CInterfaces/CCompressor.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CCounter.o : $(PRJ_ROOT_DIR)/CInterfaces/CCounter.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CDigitalInput.o : $(PRJ_ROOT_DIR)/CInterfaces/CDigitalInput.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CDigitalOutput.o : $(PRJ_ROOT_DIR)/CInterfaces/CDigitalOutput.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CDriverStation.o : $(PRJ_ROOT_DIR)/CInterfaces/CDriverStation.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CEncoder.o : $(PRJ_ROOT_DIR)/CInterfaces/CEncoder.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CGearTooth.o : $(PRJ_ROOT_DIR)/CInterfaces/CGearTooth.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CGyro.o : $(PRJ_ROOT_DIR)/CInterfaces/CGyro.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CJaguar.o : $(PRJ_ROOT_DIR)/CInterfaces/CJaguar.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CJoystick.o : $(PRJ_ROOT_DIR)/CInterfaces/CJoystick.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CPWM.o : $(PRJ_ROOT_DIR)/CInterfaces/CPWM.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CRelay.o : $(PRJ_ROOT_DIR)/CInterfaces/CRelay.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CRobotDrive.o : $(PRJ_ROOT_DIR)/CInterfaces/CRobotDrive.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CSerialPort.o : $(PRJ_ROOT_DIR)/CInterfaces/CSerialPort.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CServo.o : $(PRJ_ROOT_DIR)/CInterfaces/CServo.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CSolenoid.o : $(PRJ_ROOT_DIR)/CInterfaces/CSolenoid.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CTimer.o : $(PRJ_ROOT_DIR)/CInterfaces/CTimer.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CUltrasonic.o : $(PRJ_ROOT_DIR)/CInterfaces/CUltrasonic.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CVictor.o : $(PRJ_ROOT_DIR)/CInterfaces/CVictor.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CWatchdog.o : $(PRJ_ROOT_DIR)/CInterfaces/CWatchdog.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/SimpleCRobot.o : $(PRJ_ROOT_DIR)/CInterfaces/SimpleCRobot.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/Command.o : $(PRJ_ROOT_DIR)/Commands/Command.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/CommandGroup.o : $(PRJ_ROOT_DIR)/Commands/CommandGroup.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/CommandGroupEntry.o : $(PRJ_ROOT_DIR)/Commands/CommandGroupEntry.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/PIDCommand.o : $(PRJ_ROOT_DIR)/Commands/PIDCommand.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/PIDSubsystem.o : $(PRJ_ROOT_DIR)/Commands/PIDSubsystem.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/PrintCommand.o : $(PRJ_ROOT_DIR)/Commands/PrintCommand.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/Scheduler.o : $(PRJ_ROOT_DIR)/Commands/Scheduler.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/StartCommand.o : $(PRJ_ROOT_DIR)/Commands/StartCommand.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/Subsystem.o : $(PRJ_ROOT_DIR)/Commands/Subsystem.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/WaitCommand.o : $(PRJ_ROOT_DIR)/Commands/WaitCommand.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/WaitForChildren.o : $(PRJ_ROOT_DIR)/Commands/WaitForChildren.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Commands/WaitUntilCommand.o : $(PRJ_ROOT_DIR)/Commands/WaitUntilCommand.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Compressor.o : $(PRJ_ROOT_DIR)/Compressor.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Counter.o : $(PRJ_ROOT_DIR)/Counter.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Dashboard.o : $(PRJ_ROOT_DIR)/Dashboard.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/DigitalInput.o : $(PRJ_ROOT_DIR)/DigitalInput.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/DigitalModule.o : $(PRJ_ROOT_DIR)/DigitalModule.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/DigitalOutput.o : $(PRJ_ROOT_DIR)/DigitalOutput.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/DigitalSource.o : $(PRJ_ROOT_DIR)/DigitalSource.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/DoubleSolenoid.o : $(PRJ_ROOT_DIR)/DoubleSolenoid.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/DriverStation.o : $(PRJ_ROOT_DIR)/DriverStation.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/DriverStationEnhancedIO.o : $(PRJ_ROOT_DIR)/DriverStationEnhancedIO.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/DriverStationLCD.o : $(PRJ_ROOT_DIR)/DriverStationLCD.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Encoder.o : $(PRJ_ROOT_DIR)/Encoder.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Error.o : $(PRJ_ROOT_DIR)/Error.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/ErrorBase.o : $(PRJ_ROOT_DIR)/ErrorBase.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/GearTooth.o : $(PRJ_ROOT_DIR)/GearTooth.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Gyro.o : $(PRJ_ROOT_DIR)/Gyro.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/HiTechnicCompass.o : $(PRJ_ROOT_DIR)/HiTechnicCompass.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/I2C.o : $(PRJ_ROOT_DIR)/I2C.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/InterruptableSensorBase.o : $(PRJ_ROOT_DIR)/InterruptableSensorBase.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/IterativeRobot.o : $(PRJ_ROOT_DIR)/IterativeRobot.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Jaguar.o : $(PRJ_ROOT_DIR)/Jaguar.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Joystick.o : $(PRJ_ROOT_DIR)/Joystick.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Kinect.o : $(PRJ_ROOT_DIR)/Kinect.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/KinectStick.o : $(PRJ_ROOT_DIR)/KinectStick.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Module.o : $(PRJ_ROOT_DIR)/Module.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/MotorSafetyHelper.o : $(PRJ_ROOT_DIR)/MotorSafetyHelper.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/BooleanEntry.o : $(PRJ_ROOT_DIR)/NetworkTables/BooleanEntry.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Buffer.o : $(PRJ_ROOT_DIR)/NetworkTables/Buffer.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Confirmation.o : $(PRJ_ROOT_DIR)/NetworkTables/Confirmation.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Connection.o : $(PRJ_ROOT_DIR)/NetworkTables/Connection.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/ConnectionManager.o : $(PRJ_ROOT_DIR)/NetworkTables/ConnectionManager.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Data.o : $(PRJ_ROOT_DIR)/NetworkTables/Data.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Denial.o : $(PRJ_ROOT_DIR)/NetworkTables/Denial.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/DoubleEntry.o : $(PRJ_ROOT_DIR)/NetworkTables/DoubleEntry.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Entry.o : $(PRJ_ROOT_DIR)/NetworkTables/Entry.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/IntegerEntry.o : $(PRJ_ROOT_DIR)/NetworkTables/IntegerEntry.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Key.o : $(PRJ_ROOT_DIR)/NetworkTables/Key.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/NetworkQueue.o : $(PRJ_ROOT_DIR)/NetworkTables/NetworkQueue.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/NetworkTable.o : $(PRJ_ROOT_DIR)/NetworkTables/NetworkTable.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/OldData.o : $(PRJ_ROOT_DIR)/NetworkTables/OldData.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Reader.o : $(PRJ_ROOT_DIR)/NetworkTables/Reader.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/StringEntry.o : $(PRJ_ROOT_DIR)/NetworkTables/StringEntry.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TableAssignment.o : $(PRJ_ROOT_DIR)/NetworkTables/TableAssignment.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TableEntry.o : $(PRJ_ROOT_DIR)/NetworkTables/TableEntry.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TransactionEnd.o : $(PRJ_ROOT_DIR)/NetworkTables/TransactionEnd.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TransactionStart.o : $(PRJ_ROOT_DIR)/NetworkTables/TransactionStart.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Notifier.o : $(PRJ_ROOT_DIR)/Notifier.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/PIDController.o : $(PRJ_ROOT_DIR)/PIDController.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/PWM.o : $(PRJ_ROOT_DIR)/PWM.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Preferences.o : $(PRJ_ROOT_DIR)/Preferences.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Relay.o : $(PRJ_ROOT_DIR)/Relay.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Resource.o : $(PRJ_ROOT_DIR)/Resource.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/RobotBase.o : $(PRJ_ROOT_DIR)/RobotBase.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/RobotDrive.o : $(PRJ_ROOT_DIR)/RobotDrive.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/SPI.o : $(PRJ_ROOT_DIR)/SPI.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/SafePWM.o : $(PRJ_ROOT_DIR)/SafePWM.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/SensorBase.o : $(PRJ_ROOT_DIR)/SensorBase.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/SerialPort.o : $(PRJ_ROOT_DIR)/SerialPort.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Servo.o : $(PRJ_ROOT_DIR)/Servo.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/SimpleRobot.o : $(PRJ_ROOT_DIR)/SimpleRobot.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SendableChooser.o : $(PRJ_ROOT_DIR)/SmartDashboard/SendableChooser.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SendableGyro.o : $(PRJ_ROOT_DIR)/SmartDashboard/SendableGyro.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SendablePIDController.o : $(PRJ_ROOT_DIR)/SmartDashboard/SendablePIDController.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SmartDashboard.o : $(PRJ_ROOT_DIR)/SmartDashboard/SmartDashboard.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Solenoid.o : $(PRJ_ROOT_DIR)/Solenoid.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/SolenoidBase.o : $(PRJ_ROOT_DIR)/SolenoidBase.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Synchronized.o : $(PRJ_ROOT_DIR)/Synchronized.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Task.o : $(PRJ_ROOT_DIR)/Task.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Timer.o : $(PRJ_ROOT_DIR)/Timer.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Ultrasonic.o : $(PRJ_ROOT_DIR)/Ultrasonic.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Utility.o : $(PRJ_ROOT_DIR)/Utility.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Victor.o : $(PRJ_ROOT_DIR)/Victor.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/AxisCamera.o : $(PRJ_ROOT_DIR)/Vision/AxisCamera.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/AxisCameraParams.o : $(PRJ_ROOT_DIR)/Vision/AxisCameraParams.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/BinaryImage.o : $(PRJ_ROOT_DIR)/Vision/BinaryImage.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/ColorImage.o : $(PRJ_ROOT_DIR)/Vision/ColorImage.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/EnumCameraParameter.o : $(PRJ_ROOT_DIR)/Vision/EnumCameraParameter.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/HSLImage.o : $(PRJ_ROOT_DIR)/Vision/HSLImage.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/ImageBase.o : $(PRJ_ROOT_DIR)/Vision/ImageBase.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/IntCameraParameter.o : $(PRJ_ROOT_DIR)/Vision/IntCameraParameter.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/MonoImage.o : $(PRJ_ROOT_DIR)/Vision/MonoImage.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/PCVideoServer.o : $(PRJ_ROOT_DIR)/Vision/PCVideoServer.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/RGBImage.o : $(PRJ_ROOT_DIR)/Vision/RGBImage.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision/Threshold.o : $(PRJ_ROOT_DIR)/Vision/Threshold.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/AxisCamera.o : $(PRJ_ROOT_DIR)/Vision2009/AxisCamera.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/BaeUtilities.o : $(PRJ_ROOT_DIR)/Vision2009/BaeUtilities.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/FrcError.o : $(PRJ_ROOT_DIR)/Vision2009/FrcError.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/TrackAPI.o : $(PRJ_ROOT_DIR)/Vision2009/TrackAPI.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/VisionAPI.o : $(PRJ_ROOT_DIR)/Vision2009/VisionAPI.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+WPILib/$(MODE_DIR)/Objects/WPILib/Watchdog.o : $(PRJ_ROOT_DIR)/Watchdog.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+OBJECTS_WPILib = WPILib/$(MODE_DIR)/Objects/WPILib/ADXL345_I2C.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/ADXL345_SPI.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Accelerometer.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/AnalogChannel.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/AnalogModule.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/AnalogTrigger.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/AnalogTriggerOutput.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/AnalogIOButton.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/Button.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/ButtonScheduler.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/DigitalIOButton.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/HeldButtonScheduler.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/InternalButton.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/JoystickButton.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/NetworkButton.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/PressedButtonScheduler.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/ReleasedButtonScheduler.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CANJaguar.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CAccelerometer.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CAnalogChannel.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CCompressor.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CCounter.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CDigitalInput.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CDigitalOutput.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CDriverStation.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CEncoder.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CGearTooth.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CGyro.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CJaguar.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CJoystick.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CPWM.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CRelay.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CRobotDrive.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CSerialPort.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CServo.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CSolenoid.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CTimer.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CUltrasonic.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CVictor.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CWatchdog.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/SimpleCRobot.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/Command.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/CommandGroup.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/CommandGroupEntry.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/PIDCommand.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/PIDSubsystem.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/PrintCommand.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/Scheduler.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/StartCommand.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/Subsystem.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/WaitCommand.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/WaitForChildren.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/WaitUntilCommand.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Compressor.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Counter.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Dashboard.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/DigitalInput.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/DigitalModule.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/DigitalOutput.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/DigitalSource.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/DoubleSolenoid.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/DriverStation.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/DriverStationEnhancedIO.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/DriverStationLCD.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Encoder.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Error.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/ErrorBase.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/GearTooth.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Gyro.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/HiTechnicCompass.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/I2C.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/InterruptableSensorBase.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/IterativeRobot.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Jaguar.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Joystick.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Kinect.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/KinectStick.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Module.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/MotorSafetyHelper.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/BooleanEntry.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Buffer.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Confirmation.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Connection.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/ConnectionManager.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Data.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Denial.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/DoubleEntry.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Entry.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/IntegerEntry.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Key.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/NetworkQueue.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/NetworkTable.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/OldData.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Reader.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/StringEntry.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TableAssignment.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TableEntry.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TransactionEnd.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TransactionStart.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Notifier.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/PIDController.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/PWM.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Preferences.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Relay.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Resource.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/RobotBase.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/RobotDrive.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SPI.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SafePWM.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SensorBase.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SerialPort.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Servo.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SimpleRobot.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SendableChooser.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SendableGyro.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SendablePIDController.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SmartDashboard.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Solenoid.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SolenoidBase.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Synchronized.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Task.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Timer.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Ultrasonic.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Utility.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Victor.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/AxisCamera.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/AxisCameraParams.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/BinaryImage.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/ColorImage.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/EnumCameraParameter.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/HSLImage.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/ImageBase.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/IntCameraParameter.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/MonoImage.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/PCVideoServer.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/RGBImage.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/Threshold.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/AxisCamera.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/BaeUtilities.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/FrcError.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/TrackAPI.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/VisionAPI.o \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Watchdog.o
+
+WPILib/$(MODE_DIR)/WPILib.a : $(OBJECTS_WPILib)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi;echo "building $@"; $(TOOL_PATH)arppc crus "$@" $(OBJECTS_WPILib)
+
+WPILib/$(MODE_DIR)/WPILib_compile_file : $(FILE) ;
+
+_clean :: WPILib/$(MODE_DIR)/WPILib_clean
+
+WPILib/$(MODE_DIR)/WPILib_clean :
+ $(TRACE_FLAG)if [ -d "WPILib" ]; then cd "WPILib"; rm -rf $(MODE_DIR); fi
+
+
+# JavaCameraLib
+ifeq ($(DEBUG_MODE),1)
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_C-Compiler = -g
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_C++-Compiler = -g
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_Linker = -g
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_Partial-Image-Linker =
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_Librarian =
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_Assembler = -g
+else
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_Linker = -O2 -fstrength-reduce -fno-builtin
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_Partial-Image-Linker =
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_Librarian =
+JavaCameraLib/$(MODE_DIR)/% : DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+JavaCameraLib/$(MODE_DIR)/% : IDE_INCLUDES = -I.. -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+JavaCameraLib/$(MODE_DIR)/% : IDE_LIBRARIES =
+JavaCameraLib/$(MODE_DIR)/% : IDE_DEFINES =
+JavaCameraLib/$(MODE_DIR)/% : PROJECT_TYPE = DKM
+JavaCameraLib/$(MODE_DIR)/% : DEFINES =
+JavaCameraLib/$(MODE_DIR)/% : EXPAND_DBG = 0
+JavaCameraLib/$(MODE_DIR)/% : VX_CPU_FAMILY = ppc
+JavaCameraLib/$(MODE_DIR)/% : CPU = PPC603
+JavaCameraLib/$(MODE_DIR)/% : TOOL_FAMILY = gnu
+JavaCameraLib/$(MODE_DIR)/% : TOOL = gnu
+JavaCameraLib/$(MODE_DIR)/% : TOOL_PATH =
+JavaCameraLib/$(MODE_DIR)/% : CC_ARCH_SPEC = -mcpu=603 -mstrict-align -mno-implicit-fp -mlongcall
+JavaCameraLib/$(MODE_DIR)/% : LIBPATH =
+JavaCameraLib/$(MODE_DIR)/% : LIBS =
+JavaCameraLib/$(MODE_DIR)/% : OBJ_DIR := JavaCameraLib/$(MODE_DIR)
+
+JavaCameraLib/$(MODE_DIR)/Objects/PCVideoServer.o : $(PRJ_ROOT_DIR)/Vision/PCVideoServer.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+JavaCameraLib/$(MODE_DIR)/Objects/AxisCamera.o : $(PRJ_ROOT_DIR)/Vision/AxisCamera.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+JavaCameraLib/$(MODE_DIR)/Objects/AxisCameraParams.o : $(PRJ_ROOT_DIR)/Vision/AxisCameraParams.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+JavaCameraLib/$(MODE_DIR)/Objects/EnumCameraParameter.o : $(PRJ_ROOT_DIR)/Vision/EnumCameraParameter.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+JavaCameraLib/$(MODE_DIR)/Objects/IntCameraParameter.o : $(PRJ_ROOT_DIR)/Vision/IntCameraParameter.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+JavaCameraLib/$(MODE_DIR)/Objects/Error.o : $(PRJ_ROOT_DIR)/Error.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+JavaCameraLib/$(MODE_DIR)/Objects/ErrorBase.o : $(PRJ_ROOT_DIR)/ErrorBase.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+JavaCameraLib/$(MODE_DIR)/Objects/Task.o : $(PRJ_ROOT_DIR)/Task.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+JavaCameraLib/$(MODE_DIR)/Objects/Timer.o : $(PRJ_ROOT_DIR)/Timer.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+JavaCameraLib/$(MODE_DIR)/Objects/Synchronized.o : $(PRJ_ROOT_DIR)/Synchronized.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+JavaCameraLib/$(MODE_DIR)/Objects/Utility.o : $(PRJ_ROOT_DIR)/Utility.cpp $(FORCE_FILE_BUILD)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -DJAVA_CAMERA_LIB=1 -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+
+OBJECTS_JavaCameraLib = JavaCameraLib/$(MODE_DIR)/Objects/PCVideoServer.o \
+ JavaCameraLib/$(MODE_DIR)/Objects/AxisCamera.o \
+ JavaCameraLib/$(MODE_DIR)/Objects/AxisCameraParams.o \
+ JavaCameraLib/$(MODE_DIR)/Objects/EnumCameraParameter.o \
+ JavaCameraLib/$(MODE_DIR)/Objects/IntCameraParameter.o \
+ JavaCameraLib/$(MODE_DIR)/Objects/Error.o \
+ JavaCameraLib/$(MODE_DIR)/Objects/ErrorBase.o \
+ JavaCameraLib/$(MODE_DIR)/Objects/Task.o \
+ JavaCameraLib/$(MODE_DIR)/Objects/Timer.o \
+ JavaCameraLib/$(MODE_DIR)/Objects/Synchronized.o \
+ JavaCameraLib/$(MODE_DIR)/Objects/Utility.o
+
+JavaCameraLib/$(MODE_DIR)/JavaCameraLib.a : $(OBJECTS_JavaCameraLib)
+ $(TRACE_FLAG)if [ ! -d "`dirname "$@"`" ]; then mkdir -p "`dirname "$@"`"; fi;echo "building $@"; $(TOOL_PATH)arppc crus "$@" $(OBJECTS_JavaCameraLib)
+
+JavaCameraLib/$(MODE_DIR)/JavaCameraLib_compile_file : $(FILE) ;
+
+_clean :: JavaCameraLib/$(MODE_DIR)/JavaCameraLib_clean
+
+JavaCameraLib/$(MODE_DIR)/JavaCameraLib_clean :
+ $(TRACE_FLAG)if [ -d "JavaCameraLib" ]; then cd "JavaCameraLib"; rm -rf $(MODE_DIR); fi
+
+force :
+
+DEP_FILES := WPILib/$(MODE_DIR)/Objects/WPILib/ADXL345_I2C.d WPILib/$(MODE_DIR)/Objects/WPILib/ADXL345_SPI.d WPILib/$(MODE_DIR)/Objects/WPILib/Accelerometer.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/AnalogChannel.d WPILib/$(MODE_DIR)/Objects/WPILib/AnalogModule.d WPILib/$(MODE_DIR)/Objects/WPILib/AnalogTrigger.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/AnalogTriggerOutput.d WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/AnalogIOButton.d WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/Button.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/ButtonScheduler.d WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/DigitalIOButton.d WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/HeldButtonScheduler.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/InternalButton.d WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/JoystickButton.d WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/NetworkButton.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/PressedButtonScheduler.d WPILib/$(MODE_DIR)/Objects/WPILib/Buttons/ReleasedButtonScheduler.d WPILib/$(MODE_DIR)/Objects/WPILib/CANJaguar.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CAccelerometer.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CAnalogChannel.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CCompressor.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CCounter.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CDigitalInput.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CDigitalOutput.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CDriverStation.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CEncoder.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CGearTooth.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CGyro.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CJaguar.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CJoystick.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CPWM.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CRelay.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CRobotDrive.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CSerialPort.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CServo.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CSolenoid.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CTimer.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CUltrasonic.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CVictor.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/CWatchdog.d WPILib/$(MODE_DIR)/Objects/WPILib/CInterfaces/SimpleCRobot.d WPILib/$(MODE_DIR)/Objects/WPILib/Commands/Command.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/CommandGroup.d WPILib/$(MODE_DIR)/Objects/WPILib/Commands/CommandGroupEntry.d WPILib/$(MODE_DIR)/Objects/WPILib/Commands/PIDCommand.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/PIDSubsystem.d WPILib/$(MODE_DIR)/Objects/WPILib/Commands/PrintCommand.d WPILib/$(MODE_DIR)/Objects/WPILib/Commands/Scheduler.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/StartCommand.d WPILib/$(MODE_DIR)/Objects/WPILib/Commands/Subsystem.d WPILib/$(MODE_DIR)/Objects/WPILib/Commands/WaitCommand.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Commands/WaitForChildren.d WPILib/$(MODE_DIR)/Objects/WPILib/Commands/WaitUntilCommand.d WPILib/$(MODE_DIR)/Objects/WPILib/Compressor.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Counter.d WPILib/$(MODE_DIR)/Objects/WPILib/Dashboard.d WPILib/$(MODE_DIR)/Objects/WPILib/DigitalInput.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/DigitalModule.d WPILib/$(MODE_DIR)/Objects/WPILib/DigitalOutput.d WPILib/$(MODE_DIR)/Objects/WPILib/DigitalSource.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/DoubleSolenoid.d WPILib/$(MODE_DIR)/Objects/WPILib/DriverStation.d WPILib/$(MODE_DIR)/Objects/WPILib/DriverStationEnhancedIO.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/DriverStationLCD.d WPILib/$(MODE_DIR)/Objects/WPILib/Encoder.d WPILib/$(MODE_DIR)/Objects/WPILib/Error.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/ErrorBase.d WPILib/$(MODE_DIR)/Objects/WPILib/GearTooth.d WPILib/$(MODE_DIR)/Objects/WPILib/Gyro.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/HiTechnicCompass.d WPILib/$(MODE_DIR)/Objects/WPILib/I2C.d WPILib/$(MODE_DIR)/Objects/WPILib/InterruptableSensorBase.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/IterativeRobot.d WPILib/$(MODE_DIR)/Objects/WPILib/Jaguar.d WPILib/$(MODE_DIR)/Objects/WPILib/Joystick.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Kinect.d WPILib/$(MODE_DIR)/Objects/WPILib/KinectStick.d WPILib/$(MODE_DIR)/Objects/WPILib/Module.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/MotorSafetyHelper.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/BooleanEntry.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Buffer.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Confirmation.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Connection.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/ConnectionManager.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Data.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Denial.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/DoubleEntry.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Entry.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/IntegerEntry.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Key.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/NetworkQueue.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/NetworkTable.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/OldData.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/Reader.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/StringEntry.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TableAssignment.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TableEntry.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TransactionEnd.d WPILib/$(MODE_DIR)/Objects/WPILib/NetworkTables/TransactionStart.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Notifier.d WPILib/$(MODE_DIR)/Objects/WPILib/PIDController.d WPILib/$(MODE_DIR)/Objects/WPILib/PWM.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Preferences.d WPILib/$(MODE_DIR)/Objects/WPILib/Relay.d WPILib/$(MODE_DIR)/Objects/WPILib/Resource.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/RobotBase.d WPILib/$(MODE_DIR)/Objects/WPILib/RobotDrive.d WPILib/$(MODE_DIR)/Objects/WPILib/SPI.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SafePWM.d WPILib/$(MODE_DIR)/Objects/WPILib/SensorBase.d WPILib/$(MODE_DIR)/Objects/WPILib/SerialPort.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Servo.d WPILib/$(MODE_DIR)/Objects/WPILib/SimpleRobot.d WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SendableChooser.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SendableGyro.d WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SendablePIDController.d WPILib/$(MODE_DIR)/Objects/WPILib/SmartDashboard/SmartDashboard.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Solenoid.d WPILib/$(MODE_DIR)/Objects/WPILib/SolenoidBase.d WPILib/$(MODE_DIR)/Objects/WPILib/Synchronized.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Task.d WPILib/$(MODE_DIR)/Objects/WPILib/Timer.d WPILib/$(MODE_DIR)/Objects/WPILib/Ultrasonic.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Utility.d WPILib/$(MODE_DIR)/Objects/WPILib/Victor.d WPILib/$(MODE_DIR)/Objects/WPILib/Vision/AxisCamera.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/AxisCameraParams.d WPILib/$(MODE_DIR)/Objects/WPILib/Vision/BinaryImage.d WPILib/$(MODE_DIR)/Objects/WPILib/Vision/ColorImage.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/EnumCameraParameter.d WPILib/$(MODE_DIR)/Objects/WPILib/Vision/HSLImage.d WPILib/$(MODE_DIR)/Objects/WPILib/Vision/ImageBase.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/IntCameraParameter.d WPILib/$(MODE_DIR)/Objects/WPILib/Vision/MonoImage.d WPILib/$(MODE_DIR)/Objects/WPILib/Vision/PCVideoServer.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision/RGBImage.d WPILib/$(MODE_DIR)/Objects/WPILib/Vision/Threshold.d WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/AxisCamera.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/BaeUtilities.d WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/FrcError.d WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/TrackAPI.d \
+ WPILib/$(MODE_DIR)/Objects/WPILib/Vision2009/VisionAPI.d WPILib/$(MODE_DIR)/Objects/WPILib/Watchdog.d JavaCameraLib/$(MODE_DIR)/Objects/PCVideoServer.d \
+ JavaCameraLib/$(MODE_DIR)/Objects/AxisCamera.d JavaCameraLib/$(MODE_DIR)/Objects/AxisCameraParams.d JavaCameraLib/$(MODE_DIR)/Objects/EnumCameraParameter.d \
+ JavaCameraLib/$(MODE_DIR)/Objects/IntCameraParameter.d JavaCameraLib/$(MODE_DIR)/Objects/Error.d JavaCameraLib/$(MODE_DIR)/Objects/ErrorBase.d \
+ JavaCameraLib/$(MODE_DIR)/Objects/Task.d JavaCameraLib/$(MODE_DIR)/Objects/Timer.d JavaCameraLib/$(MODE_DIR)/Objects/Synchronized.d \
+ JavaCameraLib/$(MODE_DIR)/Objects/Utility.d
+-include $(DEP_FILES)
+
+
+
+-include $(PRJ_ROOT_DIR)/*.makefile
+
+-include *.makefile
+
+main_all : external_build $(PROJECT_TARGETS)
+ @echo "make: built targets of `pwd`"
+
+# entry point for extending the build
+external_build ::
+ @echo ""
+
+# main entry point for pre processing prior to the build
+pre_build :: $(PRE_BUILD_STEP) generate_sources
+ @echo ""
+
+# entry point for generating sources prior to the build
+generate_sources ::
+ @echo ""
+
+# main entry point for post processing after the build
+post_build :: $(POST_BUILD_STEP) deploy_output
+ @echo ""
+
+# entry point for deploying output after the build
+deploy_output ::
+ @echo ""
+
+clean :: external_clean $(CLEAN_STEP) _clean
+
+# entry point for extending the build clean
+external_clean ::
+ @echo ""
diff --git a/aos/externals/WPILib/WPILib/PWM.cpp b/aos/externals/WPILib/WPILib/PWM.cpp
new file mode 100644
index 0000000..e1991fb
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/PWM.cpp
@@ -0,0 +1,334 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "PWM.h"
+
+#include "DigitalModule.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+const UINT32 PWM::kDefaultPwmPeriod;
+const UINT32 PWM::kDefaultMinPwmHigh;
+const INT32 PWM::kPwmDisabled;
+static Resource *allocated = NULL;
+
+/**
+ * Initialize PWMs given an module and channel.
+ *
+ * This method is private and is the common path for all the constructors for creating PWM
+ * instances. Checks module and channel value ranges and allocates the appropriate channel.
+ * The allocation is only done to help users ensure that they don't double assign channels.
+ */
+void PWM::InitPWM(UINT8 moduleNumber, UINT32 channel)
+{
+ char buf[64];
+ Resource::CreateResourceObject(&allocated, tDIO::kNumSystems * kPwmChannels);
+ if (!CheckPWMModule(moduleNumber))
+ {
+ snprintf(buf, 64, "Digital Module %d", moduleNumber);
+ wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf);
+ return;
+ }
+ if (!CheckPWMChannel(channel))
+ {
+ snprintf(buf, 64, "PWM Channel %d", channel);
+ wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+ return;
+ }
+
+ snprintf(buf, 64, "PWM %d (Module: %d)", channel, moduleNumber);
+ if (allocated->Allocate((moduleNumber - 1) * kPwmChannels + channel - 1, buf) == ~0ul)
+ {
+ CloneError(allocated);
+ return;
+ }
+ m_channel = channel;
+ m_module = DigitalModule::GetInstance(moduleNumber);
+ m_module->SetPWM(m_channel, kPwmDisabled);
+ m_eliminateDeadband = false;
+
+ nUsageReporting::report(nUsageReporting::kResourceType_PWM, channel, moduleNumber - 1);
+}
+
+/**
+ * Allocate a PWM given a module and channel.
+ * Allocate a PWM using a module and channel number.
+ *
+ * @param moduleNumber The digital module (1 or 2).
+ * @param channel The PWM channel on the digital module (1..10).
+ */
+PWM::PWM(UINT8 moduleNumber, UINT32 channel)
+ : m_module(NULL)
+{
+ InitPWM(moduleNumber, channel);
+}
+
+/**
+ * Allocate a PWM in the default module given a channel.
+ *
+ * Using a default module allocate a PWM given the channel number. The default module is the first
+ * slot numerically in the cRIO chassis.
+ *
+ * @param channel The PWM channel on the digital module.
+ */
+PWM::PWM(UINT32 channel)
+ : m_module(NULL)
+{
+ InitPWM(GetDefaultDigitalModule(), channel);
+}
+
+/**
+ * Free the PWM channel.
+ *
+ * Free the resource associated with the PWM channel and set the value to 0.
+ */
+PWM::~PWM()
+{
+ if (m_module)
+ {
+ m_module->SetPWM(m_channel, kPwmDisabled);
+ allocated->Free((m_module->GetNumber() - 1) * kPwmChannels + m_channel - 1);
+ }
+}
+
+/**
+ * Optionally eliminate the deadband from a speed controller.
+ * @param eliminateDeadband If true, set the motor curve on the Jaguar to eliminate
+ * the deadband in the middle of the range. Otherwise, keep the full range without
+ * modifying any values.
+ */
+void PWM::EnableDeadbandElimination(bool eliminateDeadband)
+{
+ if (StatusIsFatal()) return;
+ m_eliminateDeadband = eliminateDeadband;
+}
+
+/**
+ * Set the bounds on the PWM values.
+ * This sets the bounds on the PWM values for a particular each type of controller. The values
+ * determine the upper and lower speeds as well as the deadband bracket.
+ * @param max The Minimum pwm value
+ * @param deadbandMax The high end of the deadband range
+ * @param center The center speed (off)
+ * @param deadbandMin The low end of the deadband range
+ * @param min The minimum pwm value
+ */
+void PWM::SetBounds(INT32 max, INT32 deadbandMax, INT32 center, INT32 deadbandMin, INT32 min)
+{
+ if (StatusIsFatal()) return;
+ m_maxPwm = max;
+ m_deadbandMaxPwm = deadbandMax;
+ m_centerPwm = center;
+ m_deadbandMinPwm = deadbandMin;
+ m_minPwm = min;
+}
+
+UINT32 PWM::GetModuleNumber()
+{
+ return m_module->GetNumber();
+}
+
+/**
+ * Set the PWM value based on a position.
+ *
+ * This is intended to be used by servos.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @param pos The position to set the servo between 0.0 and 1.0.
+ */
+void PWM::SetPosition(float pos)
+{
+ if (StatusIsFatal()) return;
+ if (pos < 0.0)
+ {
+ pos = 0.0;
+ }
+ else if (pos > 1.0)
+ {
+ pos = 1.0;
+ }
+
+ INT32 rawValue;
+ // note, need to perform the multiplication below as floating point before converting to int
+ rawValue = (INT32)( (pos * (float) GetFullRangeScaleFactor()) + GetMinNegativePwm());
+
+ wpi_assert((rawValue >= GetMinNegativePwm()) && (rawValue <= GetMaxPositivePwm()));
+ wpi_assert(rawValue != kPwmDisabled);
+
+ // send the computed pwm value to the FPGA
+ SetRaw((UINT8)rawValue);
+}
+
+/**
+ * Get the PWM value in terms of a position.
+ *
+ * This is intended to be used by servos.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @return The position the servo is set to between 0.0 and 1.0.
+ */
+float PWM::GetPosition()
+{
+ if (StatusIsFatal()) return 0.0;
+ INT32 value = GetRaw();
+ if (value < GetMinNegativePwm())
+ {
+ return 0.0;
+ }
+ else if (value > GetMaxPositivePwm())
+ {
+ return 1.0;
+ }
+ else
+ {
+ return (float)(value - GetMinNegativePwm()) / (float)GetFullRangeScaleFactor();
+ }
+}
+
+/**
+ * Set the PWM value based on a speed.
+ *
+ * This is intended to be used by speed controllers.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinPositivePwm() called.
+ * @pre SetCenterPwm() called.
+ * @pre SetMaxNegativePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @param speed The speed to set the speed controller between -1.0 and 1.0.
+ */
+void PWM::SetSpeed(float speed)
+{
+ if (StatusIsFatal()) return;
+ // clamp speed to be in the range 1.0 >= speed >= -1.0
+ if (speed < -1.0)
+ {
+ speed = -1.0;
+ }
+ else if (speed > 1.0)
+ {
+ speed = 1.0;
+ }
+
+ // calculate the desired output pwm value by scaling the speed appropriately
+ INT32 rawValue;
+ if (speed == 0.0)
+ {
+ rawValue = GetCenterPwm();
+ }
+ else if (speed > 0.0)
+ {
+ rawValue = (INT32)(speed * ((float)GetPositiveScaleFactor()) +
+ ((float) GetMinPositivePwm()) + 0.5);
+ }
+ else
+ {
+ rawValue = (INT32)(speed * ((float)GetNegativeScaleFactor()) +
+ ((float) GetMaxNegativePwm()) + 0.5);
+ }
+
+ // the above should result in a pwm_value in the valid range
+ wpi_assert((rawValue >= GetMinNegativePwm()) && (rawValue <= GetMaxPositivePwm()));
+ wpi_assert(rawValue != kPwmDisabled);
+
+ // send the computed pwm value to the FPGA
+ SetRaw((UINT8)rawValue);
+}
+
+/**
+ * Get the PWM value in terms of speed.
+ *
+ * This is intended to be used by speed controllers.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinPositivePwm() called.
+ * @pre SetMaxNegativePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @return The most recently set speed between -1.0 and 1.0.
+ */
+float PWM::GetSpeed()
+{
+ if (StatusIsFatal()) return 0.0;
+ INT32 value = GetRaw();
+ if (value > GetMaxPositivePwm())
+ {
+ return 1.0;
+ }
+ else if (value < GetMinNegativePwm())
+ {
+ return -1.0;
+ }
+ else if (value > GetMinPositivePwm())
+ {
+ return (float)(value - GetMinPositivePwm()) / (float)GetPositiveScaleFactor();
+ }
+ else if (value < GetMaxNegativePwm())
+ {
+ return (float)(value - GetMaxNegativePwm()) / (float)GetNegativeScaleFactor();
+ }
+ else
+ {
+ return 0.0;
+ }
+}
+
+/**
+ * Set the PWM value directly to the hardware.
+ *
+ * Write a raw value to a PWM channel.
+ *
+ * @param value Raw PWM value. Range 0 - 255.
+ */
+void PWM::SetRaw(UINT8 value)
+{
+ if (StatusIsFatal()) return;
+ m_module->SetPWM(m_channel, value);
+}
+
+/**
+ * Get the PWM value directly from the hardware.
+ *
+ * Read a raw value from a PWM channel.
+ *
+ * @return Raw PWM control value. Range: 0 - 255.
+ */
+UINT8 PWM::GetRaw()
+{
+ if (StatusIsFatal()) return 0;
+ return m_module->GetPWM(m_channel);
+}
+
+/**
+ * Slow down the PWM signal for old devices.
+ *
+ * @param mult The period multiplier to apply to this channel
+ */
+void PWM::SetPeriodMultiplier(PeriodMultiplier mult)
+{
+ if (StatusIsFatal()) return;
+ switch(mult)
+ {
+ case kPeriodMultiplier_4X:
+ m_module->SetPWMPeriodScale(m_channel, 3); // Squelch 3 out of 4 outputs
+ break;
+ case kPeriodMultiplier_2X:
+ m_module->SetPWMPeriodScale(m_channel, 1); // Squelch 1 out of 2 outputs
+ break;
+ case kPeriodMultiplier_1X:
+ m_module->SetPWMPeriodScale(m_channel, 0); // Don't squelch any outputs
+ break;
+ default:
+ wpi_assert(false);
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/PWM.h b/aos/externals/WPILib/WPILib/PWM.h
new file mode 100644
index 0000000..08b3242
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/PWM.h
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef PWM_H_
+#define PWM_H_
+
+#include "SensorBase.h"
+
+class DigitalModule;
+
+/**
+ * Class implements the PWM generation in the FPGA.
+ *
+ * The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They are mapped
+ * to the hardware dependent values, in this case 0-255 for the FPGA.
+ * Changes are immediately sent to the FPGA, and the update occurs at the next
+ * FPGA cycle. There is no delay.
+ *
+ * As of revision 0.1.10 of the FPGA, the FPGA interprets the 0-255 values as follows:
+ * - 255 = full "forward"
+ * - 254 to 129 = linear scaling from "full forward" to "center"
+ * - 128 = center value
+ * - 127 to 2 = linear scaling from "center" to "full reverse"
+ * - 1 = full "reverse"
+ * - 0 = disabled (i.e. PWM output is held low)
+ */
+class PWM : public SensorBase
+{
+ friend class DigitalModule;
+public:
+ typedef enum {kPeriodMultiplier_1X = 1, kPeriodMultiplier_2X = 2, kPeriodMultiplier_4X = 4} PeriodMultiplier;
+
+ explicit PWM(UINT32 channel);
+ PWM(UINT8 moduleNumber, UINT32 channel);
+ virtual ~PWM();
+ virtual void SetRaw(UINT8 value);
+ virtual UINT8 GetRaw();
+ void SetPeriodMultiplier(PeriodMultiplier mult);
+ void EnableDeadbandElimination(bool eliminateDeadband);
+ void SetBounds(INT32 max, INT32 deadbandMax, INT32 center, INT32 deadbandMin, INT32 min);
+ UINT32 GetChannel() {return m_channel;}
+ UINT32 GetModuleNumber();
+
+protected:
+ /**
+ * kDefaultPwmPeriod is "ticks" where each tick is 6.525us
+ *
+ * - 20ms periods (50 Hz) are the "safest" setting in that this works for all devices
+ * - 20ms periods seem to be desirable for Vex Motors
+ * - 20ms periods are the specified period for HS-322HD servos, but work reliably down
+ * to 10.0 ms; starting at about 8.5ms, the servo sometimes hums and get hot;
+ * by 5.0ms the hum is nearly continuous
+ * - 10ms periods work well for Victor 884
+ * - 5ms periods allows higher update rates for Luminary Micro Jaguar speed controllers.
+ * Due to the shipping firmware on the Jaguar, we can't run the update period less
+ * than 5.05 ms.
+ *
+ * kDefaultPwmPeriod is the 1x period (5.05 ms). In hardware, the period scaling is implemented as an
+ * output squelch to get longer periods for old devices.
+ *
+ * Set to 5.05 ms period / 6.525us clock = 774
+ */
+ static const UINT32 kDefaultPwmPeriod = 774;
+
+ /**
+ * kDefaultMinPwmHigh is "ticks" where each tick is 6.525us
+ *
+ * - There are 128 pwm values less than the center, so...
+ * - The minimum output pulse length is 1.5ms - 128 * 6.525us = 0.665ms
+ * - 0.665ms / 6.525us per tick = 102
+ */
+ static const UINT32 kDefaultMinPwmHigh = 102;
+
+ static const INT32 kPwmDisabled = 0;
+
+ virtual void SetPosition(float pos);
+ virtual float GetPosition();
+ virtual void SetSpeed(float speed);
+ virtual float GetSpeed();
+
+ bool m_eliminateDeadband;
+ INT32 m_maxPwm;
+ INT32 m_deadbandMaxPwm;
+ INT32 m_centerPwm;
+ INT32 m_deadbandMinPwm;
+ INT32 m_minPwm;
+
+private:
+ void InitPWM(UINT8 moduleNumber, UINT32 channel);
+ UINT32 m_channel;
+ DigitalModule *m_module;
+ INT32 GetMaxPositivePwm() { return m_maxPwm; };
+ INT32 GetMinPositivePwm() { return m_eliminateDeadband ? m_deadbandMaxPwm : m_centerPwm + 1; };
+ INT32 GetCenterPwm() { return m_centerPwm; };
+ INT32 GetMaxNegativePwm() { return m_eliminateDeadband ? m_deadbandMinPwm : m_centerPwm - 1; };
+ INT32 GetMinNegativePwm() { return m_minPwm; };
+ INT32 GetPositiveScaleFactor() {return GetMaxPositivePwm() - GetMinPositivePwm();} ///< The scale for positive speeds.
+ INT32 GetNegativeScaleFactor() {return GetMaxNegativePwm() - GetMinNegativePwm();} ///< The scale for negative speeds.
+ INT32 GetFullRangeScaleFactor() {return GetMaxPositivePwm() - GetMinNegativePwm();} ///< The scale for positions.
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Preferences.cpp b/aos/externals/WPILib/WPILib/Preferences.cpp
new file mode 100644
index 0000000..576dc3f
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Preferences.cpp
@@ -0,0 +1,613 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Preferences.h"
+
+#include "NetworkCommunication/UsageReporting.h"
+#include "NetworkTables/NetworkTable.h"
+#include "Synchronized.h"
+#include "WPIErrors.h"
+
+#include <stdio.h>
+
+/** Private NI function needed to write to the VxWorks target */
+extern "C" int Priv_SetWriteFileAllowed(UINT32 enable);
+
+/** The Preferences table name */
+static const char *kTableName = "Preferences";
+/** The value of the save field */
+static const char *kSaveField = "~S A V E~";
+/** The file to save to */
+static const char *kFileName = "/c/wpilib-preferences.ini";
+/** The characters to put between a field and value */
+static const char *kValuePrefix = "=\"";
+/** The characters to put after the value */
+static const char *kValueSuffix = "\"\n";
+/** The singleton instance */
+Preferences *Preferences::_instance = NULL;
+
+Preferences::Preferences() :
+ m_fileLock(NULL),
+ m_fileOpStarted(NULL),
+ m_tableLock(NULL),
+ m_readTask("PreferencesReadTask", (FUNCPTR)Preferences::InitReadTask),
+ m_writeTask("PreferencesWriteTask", (FUNCPTR)Preferences::InitWriteTask)
+{
+ m_fileLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+ m_fileOpStarted = semBCreate (SEM_Q_PRIORITY, SEM_EMPTY);
+ m_tableLock = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+
+ Synchronized sync(m_fileLock);
+ m_readTask.Start((UINT32)this);
+ semTake(m_fileOpStarted, WAIT_FOREVER);
+
+ NetworkTable::GetTable(kTableName)->PutBoolean(kSaveField, false);
+ NetworkTable::GetTable(kTableName)->AddChangeListenerAny(this);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Preferences, 0);
+}
+
+Preferences::~Preferences()
+{
+ semTake(m_tableLock, WAIT_FOREVER);
+ semDelete(m_tableLock);
+ semTake(m_fileLock, WAIT_FOREVER);
+ semDelete(m_fileOpStarted);
+ semDelete(m_fileLock);
+}
+
+/**
+ * Get the one and only {@link Preferences} object
+ * @return pointer to the {@link Preferences}
+ */
+Preferences *Preferences::GetInstance()
+{
+ if (_instance == NULL)
+ _instance = new Preferences;
+ return _instance;
+}
+
+/**
+ * Returns a vector of all the keys
+ * @return a vector of the keys
+ */
+std::vector<std::string> Preferences::GetKeys()
+{
+ return m_keys;
+}
+
+/**
+ * Returns the string at the given key. If this table does not have a value
+ * for that position, then the given defaultValue will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+std::string Preferences::GetString(const char *key, const char *defaultValue)
+{
+ std::string value = Get(key);
+ return value.empty() ? defaultValue : value;
+}
+
+/**
+ * Returns the string at the given key. If this table does not have a value
+ * for that position, then the given defaultValue will be returned.
+ * @param key the key
+ * @param value the buffer to copy the value into
+ * @param valueSize the size of value
+ * @param defaultValue the value to return if none exists in the table
+ * @return The size of the returned string
+ */
+int Preferences::GetString(const char *key, char *value, int valueSize, const char *defaultValue)
+{
+ std::string stringValue = GetString(key, defaultValue);
+ stringValue.copy(value, valueSize);
+ return stringValue.size();
+}
+
+/**
+ * Returns the int at the given key. If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+int Preferences::GetInt(const char *key, int defaultValue)
+{
+ std::string value = Get(key);
+ if (value.empty())
+ return defaultValue;
+
+ return strtol(value.c_str(), NULL, 0);
+}
+
+/**
+ * Returns the double at the given key. If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+double Preferences::GetDouble(const char *key, double defaultValue)
+{
+ std::string value = Get(key);
+ if (value.empty())
+ return defaultValue;
+
+ return strtod(value.c_str(), NULL);
+}
+
+/**
+ * Returns the float at the given key. If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+float Preferences::GetFloat(const char *key, float defaultValue)
+{
+ std::string value = Get(key);
+ if (value.empty())
+ return defaultValue;
+
+ return strtod(value.c_str(), NULL);
+}
+
+/**
+ * Returns the boolean at the given key. If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+bool Preferences::GetBoolean(const char *key, bool defaultValue)
+{
+ std::string value = Get(key);
+ if (value.empty())
+ return defaultValue;
+
+ if (value.compare("true") == 0)
+ return true;
+ else if (value.compare("false") == 0)
+ return false;
+
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "Boolean value does not contain \"true\" or \"false\"");
+ return false;
+}
+
+/**
+ * Returns the long (INT64) at the given key. If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+INT64 Preferences::GetLong(const char *key, INT64 defaultValue)
+{
+ std::string value = Get(key);
+ if (value.empty())
+ return defaultValue;
+
+ // Ummm... not available in our VxWorks...
+ //return strtoll(value.c_str(), NULL, 0);
+ INT64 intVal;
+ sscanf(value.c_str(), "%lld", &intVal);
+ return intVal;
+}
+
+/**
+ * Puts the given string into the preferences table.
+ *
+ * <p>The value may not have quotation marks, nor may the key
+ * have any whitespace nor an equals sign</p>
+ *
+ * <p>This will <b>NOT</b> save the value to memory between power cycles,
+ * to do that you must call {@link Preferences#Save() Save()} (which must be used with care).
+ * at some point after calling this.</p>
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutString(const char *key, const char *value)
+{
+ if (value == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "value");
+ return;
+ }
+ if (std::string(value).find_first_of("\"") != std::string::npos)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "value contains illegal characters");
+ return;
+ }
+ Put(key, value);
+}
+
+/**
+ * Puts the given int into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * <p>This will <b>NOT</b> save the value to memory between power cycles,
+ * to do that you must call {@link Preferences#Save() Save()} (which must be used with care)
+ * at some point after calling this.</p>
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutInt(const char *key, int value)
+{
+ char buf[32];
+ snprintf(buf, 32, "%d", value);
+ Put(key, buf);
+}
+
+/**
+ * Puts the given double into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * <p>This will <b>NOT</b> save the value to memory between power cycles,
+ * to do that you must call {@link Preferences#Save() Save()} (which must be used with care)
+ * at some point after calling this.</p>
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutDouble(const char *key, double value)
+{
+ char buf[32];
+ snprintf(buf, 32, "%f", value);
+ Put(key, buf);
+}
+
+/**
+ * Puts the given float into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * <p>This will <b>NOT</b> save the value to memory between power cycles,
+ * to do that you must call {@link Preferences#Save() Save()} (which must be used with care)
+ * at some point after calling this.</p>
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutFloat(const char *key, float value)
+{
+ char buf[32];
+ snprintf(buf, 32, "%f", value);
+ Put(key, buf);
+}
+
+/**
+ * Puts the given boolean into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * <p>This will <b>NOT</b> save the value to memory between power cycles,
+ * to do that you must call {@link Preferences#Save() Save()} (which must be used with care)
+ * at some point after calling this.</p>
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutBoolean(const char *key, bool value)
+{
+ Put(key, value ? "true" : "false");
+}
+
+/**
+ * Puts the given long (INT64) into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * <p>This will <b>NOT</b> save the value to memory between power cycles,
+ * to do that you must call {@link Preferences#Save() Save()} (which must be used with care)
+ * at some point after calling this.</p>
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutLong(const char *key, INT64 value)
+{
+ char buf[32];
+ snprintf(buf, 32, "%lld", value);
+ Put(key, buf);
+}
+
+/**
+ * Saves the preferences to a file on the cRIO.
+ *
+ * <p>This should <b>NOT</b> be called often.
+ * Too many writes can damage the cRIO's flash memory.
+ * While it is ok to save once or twice a match, this should never
+ * be called every run of {@link IterativeRobot#TeleopPeriodic()}, etc.</p>
+ *
+ * <p>The actual writing of the file is done in a separate thread.
+ * However, any call to a get or put method will wait until the table is fully saved before continuing.</p>
+ */
+void Preferences::Save()
+{
+ Synchronized sync(m_fileLock);
+ m_writeTask.Start((UINT32)this);
+ semTake(m_fileOpStarted, WAIT_FOREVER);
+}
+
+/**
+ * Returns whether or not there is a key with the given name.
+ * @param key the key
+ * @return if there is a value at the given key
+ */
+bool Preferences::ContainsKey(const char *key)
+{
+ return !Get(key).empty();
+}
+
+/**
+ * Remove a preference
+ * @param key the key
+ */
+void Preferences::Remove(const char *key)
+{
+ m_values.erase(std::string(key));
+ std::vector<std::string>::iterator it = m_keys.begin();
+ for (; it != m_keys.end(); it++)
+ {
+ if (it->compare(key) == 0)
+ {
+ m_keys.erase(it);
+ break;
+ }
+ }
+}
+
+/**
+ * Returns the value at the given key.
+ * @param key the key
+ * @return the value (or empty if none exists)
+ */
+std::string Preferences::Get(const char *key)
+{
+ Synchronized sync(m_tableLock);
+ if (key == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "key");
+ return std::string("");
+ }
+ return m_values[std::string(key)];
+}
+
+/**
+ * Puts the given value into the given key position
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::Put(const char *key, std::string value)
+{
+ Synchronized sync(m_tableLock);
+ if (key == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "key");
+ return;
+ }
+
+ if (std::string(key).find_first_of("=\n\r \t\"") != std::string::npos)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "key contains illegal characters");
+ return;
+ }
+
+ std::pair<StringMap::iterator, bool> ret =
+ m_values.insert(StringMap::value_type(key, value));
+ if (ret.second)
+ m_keys.push_back(key);
+ else
+ ret.first->second = value;
+
+ NetworkTable::GetTable(kTableName)->PutString(key, value);
+}
+
+/**
+ * The internal method to read from a file.
+ * This will be called in its own thread when the preferences singleton is
+ * first created.
+ */
+void Preferences::ReadTaskRun()
+{
+ Synchronized sync(m_tableLock);
+ semGive(m_fileOpStarted);
+
+ std::string comment;
+
+ FILE *file = NULL;
+ file = fopen(kFileName, "r");
+
+ if (file != NULL)
+ {
+ std::string buffer;
+ while (true)
+ {
+ char value;
+ do
+ {
+ value = fgetc(file);
+ } while (value == ' ' || value == '\t');
+
+ if (value == '\n' || value == ';')
+ {
+ if (value == '\n')
+ {
+ comment += "\n";
+ }
+ else
+ {
+ buffer.clear();
+ for (; value != '\n' && !feof(file); value = fgetc(file))
+ buffer += value;
+ buffer += '\n';
+ comment += buffer;
+ }
+ }
+ else if (value == '[')
+ {
+ // Find the end of the section and the new line after it and throw it away
+ for (; value != ']' && !feof(file); value = fgetc(file));
+ for (; value != '\n' && !feof(file); value = fgetc(file));
+ }
+ else
+ {
+ buffer.clear();
+ for (; value != '=' && !feof(file); )
+ {
+ buffer += value;
+ do
+ {
+ value = fgetc(file);
+ } while (value == ' ' || value == '\t');
+ }
+ std::string name = buffer;
+ buffer.clear();
+
+ bool shouldBreak = false;
+
+ do
+ {
+ value = fgetc(file);
+ } while (value == ' ' || value == '\t');
+
+ if (value == '"')
+ {
+ for (value = fgetc(file); value != '"' && !feof(file); value = fgetc(file))
+ buffer += value;
+
+ // Clear the line
+ while (fgetc(file) != '\n' && !feof(file));
+ }
+ else
+ {
+ for (; value != '\n' && !feof(file);)
+ {
+ buffer += value;
+ do
+ {
+ value = fgetc(file);
+ } while (value == ' ' || value == '\t');
+ }
+ if (feof(file))
+ shouldBreak = true;
+ }
+
+ std::string value = buffer;
+
+ if (!name.empty() && !value.empty())
+ {
+ m_keys.push_back(name);
+ m_values.insert(std::pair<std::string, std::string>(name, value));
+ NetworkTable::GetTable(kTableName)->PutString(name, value);
+
+ if (!comment.empty())
+ {
+ m_comments.insert(std::pair<std::string, std::string>(name, comment));
+ comment.clear();
+ }
+ }
+
+ if (shouldBreak)
+ break;
+ }
+ }
+ }
+ else
+ {
+ wpi_setWPIErrorWithContext(NoAvailableResources, "Failed to open preferences file.");
+ }
+
+ if (file != NULL)
+ fclose(file);
+
+ if (!comment.empty())
+ m_endComment = comment;
+}
+
+/**
+ * Internal method that actually writes the table to a file.
+ * This is called in its own thread when {@link Preferences#Save() Save()} is called.
+ */
+void Preferences::WriteTaskRun()
+{
+ Synchronized sync(m_tableLock);
+ semGive(m_fileOpStarted);
+
+ FILE *file = NULL;
+ Priv_SetWriteFileAllowed(1);
+ file = fopen(kFileName, "w");
+
+ fputs("[Preferences]\n", file);
+ std::vector<std::string>::iterator it = m_keys.begin();
+ for (; it != m_keys.end(); it++)
+ {
+ std::string key = *it;
+ std::string value = m_values[key];
+ std::string comment = m_comments[key];
+
+ if (!comment.empty())
+ fputs(comment.c_str(), file);
+
+ fputs(key.c_str(), file);
+ fputs(kValuePrefix, file);
+ fputs(value.c_str(), file);
+ fputs(kValueSuffix, file);
+ }
+
+ if (!m_endComment.empty())
+ fputs(m_endComment.c_str(), file);
+
+ if (file != NULL)
+ fclose(file);
+
+ NetworkTable::GetTable(kTableName)->PutBoolean(kSaveField, false);
+}
+
+void Preferences::ValueChanged(NetworkTable *table, const char *name, NetworkTables_Types type)
+{
+ if (strcmp(name, kSaveField) == 0)
+ {
+ if (table->GetBoolean(kSaveField))
+ Save();
+ }
+ else
+ {
+ Synchronized sync(m_tableLock);
+
+ std::string key = name;
+ if (key.find_first_of("=\n\r \t") != std::string::npos)
+ {
+ // The key is bogus... ignore it
+ }
+ else if (table->GetString(key).find_first_of("\"") != std::string::npos)
+ {
+ table->PutString(key, "\"");
+ m_values.erase(key);
+ std::vector<std::string>::iterator it = m_keys.begin();
+ for (; it != m_keys.end(); it++)
+ {
+ if (it->compare(name) == 0)
+ {
+ m_keys.erase(it);
+ break;
+ }
+ }
+ }
+ else
+ {
+ std::pair<StringMap::iterator, bool> ret =
+ m_values.insert(StringMap::value_type(key, table->GetString(key)));
+ if (ret.second)
+ m_keys.push_back(key);
+ else
+ ret.first->second = table->GetString(key);
+ }
+ }
+}
+
+void Preferences::ValueConfirmed(NetworkTable *table, const char *name, NetworkTables_Types type)
+{
+}
diff --git a/aos/externals/WPILib/WPILib/Preferences.h b/aos/externals/WPILib/WPILib/Preferences.h
new file mode 100644
index 0000000..507fd67
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Preferences.h
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __PREFERENCES_H__
+#define __PREFERENCES_H__
+
+#include "ErrorBase.h"
+#include "NetworkTables/NetworkTableChangeListener.h"
+#include "Task.h"
+#include <map>
+#include <semLib.h>
+#include <string>
+#include <vector>
+
+/**
+ * The preferences class provides a relatively simple way to save important values to
+ * the cRIO to access the next time the cRIO is booted.
+ *
+ * <p>This class loads and saves from a file
+ * inside the cRIO. The user can not access the file directly, but may modify values at specific
+ * fields which will then be saved to the file when {@link Preferences#Save() Save()} is called.</p>
+ *
+ * <p>This class is thread safe.</p>
+ *
+ * <p>This will also interact with {@link NetworkTable} by creating a table called "Preferences" with all the
+ * key-value pairs. To save using {@link NetworkTable}, simply set the boolean at position "~S A V E~" to true.
+ * Also, if the value of any variable is " in the {@link NetworkTable}, then that represents non-existence in the
+ * {@link Preferences} table</p>
+ */
+class Preferences : public ErrorBase, public NetworkTableChangeListener
+{
+public:
+ static Preferences *GetInstance();
+
+ std::vector<std::string> GetKeys();
+ std::string GetString(const char *key, const char *defaultValue = "");
+ int GetString(const char *key, char *value, int valueSize, const char *defaultValue = "");
+ int GetInt(const char *key, int defaultValue = 0);
+ double GetDouble(const char *key, double defaultValue = 0.0);
+ float GetFloat(const char *key, float defaultValue = 0.0);
+ bool GetBoolean(const char *key, bool defaultValue = false);
+ INT64 GetLong(const char *key, INT64 defaultValue = 0);
+ void PutString(const char *key, const char *value);
+ void PutInt(const char *key, int value);
+ void PutDouble(const char *key, double value);
+ void PutFloat(const char *key, float value);
+ void PutBoolean(const char *key, bool value);
+ void PutLong(const char *key, INT64 value);
+ void Save();
+ bool ContainsKey(const char *key);
+ void Remove(const char *key);
+
+protected:
+ Preferences();
+ virtual ~Preferences();
+
+private:
+ std::string Get(const char *key);
+ void Put(const char *key, std::string value);
+
+ void ReadTaskRun();
+ void WriteTaskRun();
+
+ virtual void ValueChanged(NetworkTable *table, const char *name, NetworkTables_Types type);
+ virtual void ValueConfirmed(NetworkTable *table, const char *name, NetworkTables_Types type);
+
+ static int InitReadTask(Preferences *obj) {obj->ReadTaskRun();return 0;}
+ static int InitWriteTask(Preferences *obj) {obj->WriteTaskRun();return 0;}
+
+ static Preferences *_instance;
+
+ /** The semaphore for accessing the file */
+ SEM_ID m_fileLock;
+ /** The semaphore for beginning reads and writes to the file */
+ SEM_ID m_fileOpStarted;
+ /** The semaphore for reading from the table */
+ SEM_ID m_tableLock;
+ typedef std::map<std::string, std::string> StringMap;
+ /** The actual values (String->String) */
+ StringMap m_values;
+ /** The keys in the order they were read from the file */
+ std::vector<std::string> m_keys;
+ /** The comments that were in the file sorted by which key they appeared over (String->Comment) */
+ StringMap m_comments;
+ /** The comment at the end of the file */
+ std::string m_endComment;
+ Task m_readTask;
+ Task m_writeTask;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Relay.cpp b/aos/externals/WPILib/WPILib/Relay.cpp
new file mode 100644
index 0000000..9b52a68
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Relay.cpp
@@ -0,0 +1,184 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Relay.h"
+
+#include "DigitalModule.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+// Allocate each direction separately.
+static Resource *relayChannels = NULL;
+
+/**
+ * Common relay intitialization methode.
+ * This code is common to all Relay constructors and initializes the relay and reserves
+ * all resources that need to be locked. Initially the relay is set to both lines at 0v.
+ * @param slot The module slot number this relay is connected to.
+ *
+ * @param moduleNumber The digital module this relay is connected to (1 or 2).
+ */
+void Relay::InitRelay (UINT8 moduleNumber)
+{
+ char buf[64];
+ Resource::CreateResourceObject(&relayChannels, tDIO::kNumSystems * kRelayChannels * 2);
+ if (!SensorBase::CheckRelayModule(moduleNumber))
+ {
+ snprintf(buf, 64, "Digital Module %d", moduleNumber);
+ wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf);
+ return;
+ }
+ if (!SensorBase::CheckRelayChannel(m_channel))
+ {
+ snprintf(buf, 64, "Relay Channel %d", m_channel);
+ wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+ return;
+ }
+
+ if (m_direction == kBothDirections || m_direction == kForwardOnly)
+ {
+ snprintf(buf, 64, "Forward Relay %d (Module: %d)", m_channel, moduleNumber);
+ if (relayChannels->Allocate(((moduleNumber - 1) * kRelayChannels + m_channel - 1) * 2, buf) == ~0ul)
+ {
+ CloneError(relayChannels);
+ return;
+ }
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Relay, m_channel, moduleNumber - 1);
+ }
+ if (m_direction == kBothDirections || m_direction == kReverseOnly)
+ {
+ snprintf(buf, 64, "Reverse Relay %d (Module: %d)", m_channel, moduleNumber);
+ if (relayChannels->Allocate(((moduleNumber - 1) * kRelayChannels + m_channel - 1) * 2 + 1, buf) == ~0ul)
+ {
+ CloneError(relayChannels);
+ return;
+ }
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Relay, m_channel + 128, moduleNumber - 1);
+ }
+ m_module = DigitalModule::GetInstance(moduleNumber);
+ m_module->SetRelayForward(m_channel, false);
+ m_module->SetRelayReverse(m_channel, false);
+}
+
+/**
+ * Relay constructor given the module and the channel.
+ *
+ * @param moduleNumber The digital module this relay is connected to (1 or 2).
+ * @param channel The channel number within the module for this relay.
+ * @param direction The direction that the Relay object will control.
+ */
+Relay::Relay(UINT8 moduleNumber, UINT32 channel, Relay::Direction direction)
+ : m_channel (channel)
+ , m_direction (direction)
+{
+ InitRelay(moduleNumber);
+}
+
+/**
+ * Relay constructor given a channel only where the default digital module is used.
+ * @param channel The channel number within the default module for this relay.
+ * @param direction The direction that the Relay object will control.
+ */
+Relay::Relay(UINT32 channel, Relay::Direction direction)
+ : m_channel (channel)
+ , m_direction (direction)
+{
+ InitRelay(GetDefaultDigitalModule());
+}
+
+/**
+ * Free the resource associated with a relay.
+ * The relay channels are set to free and the relay output is turned off.
+ */
+Relay::~Relay()
+{
+ m_module->SetRelayForward(m_channel, false);
+ m_module->SetRelayReverse(m_channel, false);
+
+ if (m_direction == kBothDirections || m_direction == kForwardOnly)
+ {
+ relayChannels->Free(((m_module->GetNumber() - 1) * kRelayChannels + m_channel - 1) * 2);
+ }
+ if (m_direction == kBothDirections || m_direction == kReverseOnly)
+ {
+ relayChannels->Free(((m_module->GetNumber() - 1) * kRelayChannels + m_channel - 1) * 2 + 1);
+ }
+}
+
+/**
+ * Set the relay state.
+ *
+ * Valid values depend on which directions of the relay are controlled by the object.
+ *
+ * When set to kBothDirections, the relay can be any of the four states:
+ * 0v-0v, 0v-12v, 12v-0v, 12v-12v
+ *
+ * When set to kForwardOnly or kReverseOnly, you can specify the constant for the
+ * direction or you can simply specify kOff and kOn. Using only kOff and kOn is
+ * recommended.
+ *
+ * @param value The state to set the relay.
+ */
+void Relay::Set(Relay::Value value)
+{
+ if (StatusIsFatal()) return;
+ switch (value)
+ {
+ case kOff:
+ if (m_direction == kBothDirections || m_direction == kForwardOnly)
+ {
+ m_module->SetRelayForward(m_channel, false);
+ }
+ if (m_direction == kBothDirections || m_direction == kReverseOnly)
+ {
+ m_module->SetRelayReverse(m_channel, false);
+ }
+ break;
+ case kOn:
+ if (m_direction == kBothDirections || m_direction == kForwardOnly)
+ {
+ m_module->SetRelayForward(m_channel, true);
+ }
+ if (m_direction == kBothDirections || m_direction == kReverseOnly)
+ {
+ m_module->SetRelayReverse(m_channel, true);
+ }
+ break;
+ case kForward:
+ if (m_direction == kReverseOnly)
+ {
+ wpi_setWPIError(IncompatibleMode);
+ break;
+ }
+ if (m_direction == kBothDirections || m_direction == kForwardOnly)
+ {
+ m_module->SetRelayForward(m_channel, true);
+ }
+ if (m_direction == kBothDirections)
+ {
+ m_module->SetRelayReverse(m_channel, false);
+ }
+ break;
+ case kReverse:
+ if (m_direction == kForwardOnly)
+ {
+ wpi_setWPIError(IncompatibleMode);
+ break;
+ }
+ if (m_direction == kBothDirections)
+ {
+ m_module->SetRelayForward(m_channel, false);
+ }
+ if (m_direction == kBothDirections || m_direction == kReverseOnly)
+ {
+ m_module->SetRelayReverse(m_channel, true);
+ }
+ break;
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/Relay.h b/aos/externals/WPILib/WPILib/Relay.h
new file mode 100644
index 0000000..c2864ea
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Relay.h
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef RELAY_H_
+#define RELAY_H_
+
+#include "SensorBase.h"
+
+class DigitalModule;
+
+/**
+ * Class for Spike style relay outputs.
+ * Relays are intended to be connected to spikes or similar relays. The relay channels controls
+ * a pair of pins that are either both off, one on, the other on, or both on. This translates into
+ * two spike outputs at 0v, one at 12v and one at 0v, one at 0v and the other at 12v, or two
+ * spike outputs at 12V. This allows off, full forward, or full reverse control of motors without
+ * variable speed. It also allows the two channels (forward and reverse) to be used independently
+ * for something that does not care about voltage polatiry (like a solenoid).
+ */
+class Relay : public SensorBase {
+public:
+ typedef enum {kOff, kOn, kForward, kReverse} Value;
+ typedef enum {kBothDirections, kForwardOnly, kReverseOnly} Direction;
+
+ Relay(UINT32 channel, Direction direction = kBothDirections);
+ Relay(UINT8 moduleNumber, UINT32 channel, Direction direction = kBothDirections);
+ virtual ~Relay();
+
+ void Set(Value value);
+
+private:
+ void InitRelay(UINT8 moduleNumber);
+
+ UINT32 m_channel;
+ Direction m_direction;
+ DigitalModule *m_module;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Resource.cpp b/aos/externals/WPILib/WPILib/Resource.cpp
new file mode 100644
index 0000000..ccbf863
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Resource.cpp
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Resource.h"
+#include "WPIErrors.h"
+#include "ErrorBase.h"
+
+Resource *Resource::m_resourceList = NULL;
+Semaphore Resource::m_createLock;
+
+/**
+ * Allocate storage for a new instance of Resource.
+ * Allocate a bool array of values that will get initialized to indicate that no resources
+ * have been allocated yet. The indicies of the resources are 0..size-1.
+ * This constructor will be called while m_createLock is held.
+ */
+Resource::Resource(UINT32 elements)
+{
+ m_size = elements;
+ m_isAllocated = new bool[m_size];
+ for (UINT32 i=0; i < m_size; i++)
+ m_isAllocated[i] = false;
+ m_nextResource = m_resourceList;
+ m_resourceList = this;
+}
+
+/*static*/ void Resource::CreateResourceObject(Resource **r, UINT32 elements)
+{
+ Synchronized sync(m_createLock);
+ if (*r == NULL)
+ *r = new Resource(elements);
+}
+
+/**
+ * Delete the allocated array or resources.
+ * This happens when the module is unloaded (provided it was statically allocated).
+ */
+Resource::~Resource()
+{
+ delete[] m_isAllocated;
+}
+
+/**
+ * Allocate a resource.
+ * When a resource is requested, mark it allocated. In this case, a free resource value
+ * within the range is located and returned after it is marked allocated.
+ */
+UINT32 Resource::Allocate(const char *resourceDesc)
+{
+ Synchronized sync(m_allocateLock);
+ for (UINT32 i=0; i < m_size; i++)
+ {
+ if (!m_isAllocated[i])
+ {
+ m_isAllocated[i] = true;
+ return i;
+ }
+ }
+ wpi_setWPIErrorWithContext(NoAvailableResources, resourceDesc);
+ return ~0ul;
+}
+
+/**
+ * Allocate a specific resource value.
+ * The user requests a specific resource value, i.e. channel number and it is verified
+ * unallocated, then returned.
+ */
+UINT32 Resource::Allocate(UINT32 index, const char *resourceDesc)
+{
+ Synchronized sync(m_allocateLock);
+ if (index >= m_size)
+ {
+ wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, resourceDesc);
+ return ~0ul;
+ }
+ if ( m_isAllocated[index] )
+ {
+ wpi_setWPIErrorWithContext(ResourceAlreadyAllocated, resourceDesc);
+ return ~0ul;
+ }
+ m_isAllocated[index] = true;
+ return index;
+}
+
+
+/**
+ * Free an allocated resource.
+ * After a resource is no longer needed, for example a destructor is called for a channel assignment
+ * class, Free will release the resource value so it can be reused somewhere else in the program.
+ */
+void Resource::Free(UINT32 index)
+{
+ Synchronized sync(m_allocateLock);
+ if (index == ~0ul) return;
+ if (index >= m_size)
+ {
+ wpi_setWPIError(NotAllocated);
+ return;
+ }
+ if (!m_isAllocated[index])
+ {
+ wpi_setWPIError(NotAllocated);
+ return;
+ }
+ m_isAllocated[index] = false;
+}
diff --git a/aos/externals/WPILib/WPILib/Resource.h b/aos/externals/WPILib/WPILib/Resource.h
new file mode 100644
index 0000000..20e7147
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Resource.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef RESOURCE_H_
+#define RESOURCE_H_
+
+#include "ErrorBase.h"
+#include "Synchronized.h"
+#include <vxWorks.h>
+
+/**
+ * Track resources in the program.
+ * The Resource class is a convienent way of keeping track of allocated arbitrary resources
+ * in the program. Resources are just indicies that have an lower and upper bound that are
+ * tracked by this class. In the library they are used for tracking allocation of hardware channels
+ * but this is purely arbitrary. The resource class does not do any actual allocation, but
+ * simply tracks if a given index is currently in use.
+ *
+ * WARNING: this should only be statically allocated. When the program loads into memory all the
+ * static constructors are called. At that time a linked list of all the "Resources" is created.
+ * Then when the program actually starts - in the Robot constructor, all resources are initialized.
+ * This ensures that the program is restartable in memory without having to unload/reload.
+ */
+class Resource : public ErrorBase
+{
+public:
+ virtual ~Resource();
+ static void CreateResourceObject(Resource **r, UINT32 elements);
+ UINT32 Allocate(const char *resourceDesc);
+ UINT32 Allocate(UINT32 index, const char *resourceDesc);
+ void Free(UINT32 index);
+
+protected:
+ explicit Resource(UINT32 size);
+
+private:
+ bool *m_isAllocated;
+ Semaphore m_allocateLock;
+ UINT32 m_size;
+ Resource *m_nextResource;
+
+ static Semaphore m_createLock;
+ static Resource *m_resourceList;
+
+ DISALLOW_COPY_AND_ASSIGN(Resource);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/RobotBase.cpp b/aos/externals/WPILib/WPILib/RobotBase.cpp
new file mode 100644
index 0000000..a658c3d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/RobotBase.cpp
@@ -0,0 +1,205 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "RobotBase.h"
+
+#include "DriverStation.h"
+#include "NetworkCommunication/FRCComm.h"
+#include "NetworkCommunication/symModuleLink.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Utility.h"
+#include <moduleLib.h>
+#include <taskLib.h>
+#include <unldLib.h>
+
+RobotBase* RobotBase::m_instance = NULL;
+
+void RobotBase::setInstance(RobotBase* robot)
+{
+ wpi_assert(m_instance == NULL);
+ m_instance = robot;
+}
+
+RobotBase &RobotBase::getInstance()
+{
+ return *m_instance;
+}
+
+/**
+ * Constructor for a generic robot program.
+ * User code should be placed in the constuctor that runs before the Autonomous or Operator
+ * Control period starts. The constructor will run to completion before Autonomous is entered.
+ *
+ * This must be used to ensure that the communications code starts. In the future it would be
+ * nice to put this code into it's own task that loads on boot so ensure that it runs.
+ */
+RobotBase::RobotBase()
+ : m_task (NULL)
+ , m_ds (NULL)
+{
+ m_ds = DriverStation::GetInstance();
+}
+
+/**
+ * Free the resources for a RobotBase class.
+ * This includes deleting all classes that might have been allocated as Singletons to they
+ * would never be deleted except here.
+ */
+RobotBase::~RobotBase()
+{
+ SensorBase::DeleteSingletons();
+ delete m_task;
+ m_task = NULL;
+ m_instance = NULL;
+}
+
+/**
+ * Check on the overall status of the system.
+ *
+ * @return Is the system active (i.e. PWM motor outputs, etc. enabled)?
+ */
+bool RobotBase::IsSystemActive()
+{
+ return m_watchdog.IsSystemActive();
+}
+
+/**
+ * Return the instance of the Watchdog timer.
+ * Get the watchdog timer so the user program can either disable it or feed it when
+ * necessary.
+ */
+Watchdog &RobotBase::GetWatchdog()
+{
+ return m_watchdog;
+}
+
+/**
+ * Determine if the Robot is currently enabled.
+ * @return True if the Robot is currently enabled by the field controls.
+ */
+bool RobotBase::IsEnabled()
+{
+ return m_ds->IsEnabled();
+}
+
+/**
+ * Determine if the Robot is currently disabled.
+ * @return True if the Robot is currently disabled by the field controls.
+ */
+bool RobotBase::IsDisabled()
+{
+ return m_ds->IsDisabled();
+}
+
+/**
+ * Determine if the robot is currently in Autnomous mode.
+ * @return True if the robot is currently operating Autonomously as determined by the field controls.
+ */
+bool RobotBase::IsAutonomous()
+{
+ return m_ds->IsAutonomous();
+}
+
+/**
+ * Determine if the robot is currently in Operator Control mode.
+ * @return True if the robot is currently operating in Tele-Op mode as determined by the field controls.
+ */
+bool RobotBase::IsOperatorControl()
+{
+ return m_ds->IsOperatorControl();
+}
+
+/**
+ * Indicates if new data is available from the driver station.
+ * @return Has new data arrived over the network since the last time this function was called?
+ */
+bool RobotBase::IsNewDataAvailable()
+{
+ return m_ds->IsNewControlData();
+}
+
+/**
+ * Static interface that will start the competition in the new task.
+ */
+void RobotBase::robotTask(FUNCPTR factory, Task *task)
+{
+ RobotBase::setInstance((RobotBase*)factory());
+ RobotBase::getInstance().m_task = task;
+ RobotBase::getInstance().StartCompetition();
+}
+
+/**
+ *
+ * Start the robot code.
+ * This function starts the robot code running by spawning a task. Currently tasks seemed to be
+ * started by LVRT without setting the VX_FP_TASK flag so floating point context is not saved on
+ * interrupts. Therefore the program experiences hard to debug and unpredictable results. So the
+ * LVRT code starts this function, and it, in turn, starts the actual user program.
+ */
+void RobotBase::startRobotTask(FUNCPTR factory)
+{
+#ifdef SVN_REV
+ if (strlen(SVN_REV))
+ {
+ printf("WPILib was compiled from SVN revision %s\n", SVN_REV);
+ }
+ else
+ {
+ printf("WPILib was compiled from a location that is not source controlled.\n");
+ }
+#else
+ printf("WPILib was compiled without -D'SVN_REV=nnnn'\n");
+#endif
+
+ // Check for startup code already running
+ INT32 oldId = taskNameToId("FRC_RobotTask");
+ if (oldId != ERROR)
+ {
+ // Find the startup code module.
+ char moduleName[256];
+ moduleNameFindBySymbolName("FRC_UserProgram_StartupLibraryInit", moduleName);
+ MODULE_ID startupModId = moduleFindByName(moduleName);
+ if (startupModId != NULL)
+ {
+ // Remove the startup code.
+ unldByModuleId(startupModId, 0);
+ printf("!!! Error: Default code was still running... It was unloaded for you... Please try again.\n");
+ return;
+ }
+ // This case should no longer get hit.
+ printf("!!! Error: Other robot code is still running... Unload it and then try again.\n");
+ return;
+ }
+
+ // Let the framework know that we are starting a new user program so the Driver Station can disable.
+ FRC_NetworkCommunication_observeUserProgramStarting();
+
+ // Let the Usage Reporting framework know that there is a C++ program running
+ nUsageReporting::report(nUsageReporting::kResourceType_Language, nUsageReporting::kLanguage_CPlusPlus);
+
+ // Start robot task
+ // This is done to ensure that the C++ robot task is spawned with the floating point
+ // context save parameter.
+ Task *task = new Task("RobotTask", (FUNCPTR)RobotBase::robotTask, Task::kDefaultPriority, 64000);
+ task->Start((INT32)factory, (INT32)task);
+}
+
+/**
+ * This class exists for the sole purpose of getting its destructor called when the module unloads.
+ * Before the module is done unloading, we need to delete the RobotBase derived singleton. This should delete
+ * the other remaining singletons that were registered. This should also stop all tasks that are using
+ * the Task class.
+ */
+class RobotDeleter
+{
+public:
+ RobotDeleter() {}
+ ~RobotDeleter()
+ {
+ delete &RobotBase::getInstance();
+ }
+};
+static RobotDeleter g_robotDeleter;
diff --git a/aos/externals/WPILib/WPILib/RobotBase.h b/aos/externals/WPILib/WPILib/RobotBase.h
new file mode 100644
index 0000000..358dadc
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/RobotBase.h
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef ROBOT_H_
+#define ROBOT_H_
+
+#include "Base.h"
+#include "Task.h"
+#include "Watchdog.h"
+
+class DriverStation;
+
+#define START_ROBOT_CLASS(_ClassName_) \
+ RobotBase *FRC_userClassFactory() \
+ { \
+ return new _ClassName_(); \
+ } \
+ extern "C" { \
+ INT32 FRC_UserProgram_StartupLibraryInit() \
+ { \
+ RobotBase::startRobotTask((FUNCPTR)FRC_userClassFactory); \
+ return 0; \
+ } \
+ }
+
+/**
+ * Implement a Robot Program framework.
+ * The RobotBase class is intended to be subclassed by a user creating a robot program.
+ * Overridden Autonomous() and OperatorControl() methods are called at the appropriate time
+ * as the match proceeds. In the current implementation, the Autonomous code will run to
+ * completion before the OperatorControl code could start. In the future the Autonomous code
+ * might be spawned as a task, then killed at the end of the Autonomous period.
+ */
+class RobotBase {
+ friend class RobotDeleter;
+public:
+ static RobotBase &getInstance();
+ static void setInstance(RobotBase* robot);
+
+ bool IsEnabled();
+ bool IsDisabled();
+ bool IsAutonomous();
+ bool IsOperatorControl();
+ bool IsSystemActive();
+ bool IsNewDataAvailable();
+ Watchdog &GetWatchdog();
+ static void startRobotTask(FUNCPTR factory);
+ static void robotTask(FUNCPTR factory, Task *task);
+
+protected:
+ virtual ~RobotBase();
+ virtual void StartCompetition() = 0;
+ RobotBase();
+
+ Task *m_task;
+ Watchdog m_watchdog;
+ DriverStation *m_ds;
+
+private:
+ static RobotBase *m_instance;
+ DISALLOW_COPY_AND_ASSIGN(RobotBase);
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/RobotDrive.cpp b/aos/externals/WPILib/WPILib/RobotDrive.cpp
new file mode 100644
index 0000000..2d54d22
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/RobotDrive.cpp
@@ -0,0 +1,734 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "RobotDrive.h"
+
+#include "CANJaguar.h"
+#include "GenericHID.h"
+#include "Joystick.h"
+#include "Jaguar.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+#include <math.h>
+
+#define max(x, y) (((x) > (y)) ? (x) : (y))
+
+const INT32 RobotDrive::kMaxNumberOfMotors;
+
+/*
+ * Driving functions
+ * These functions provide an interface to multiple motors that is used for C programming
+ * The Drive(speed, direction) function is the main part of the set that makes it easy
+ * to set speeds and direction independently in one call.
+ */
+
+/**
+ * Common function to initialize all the robot drive constructors.
+ * Create a motor safety object (the real reason for the common code) and
+ * initialize all the motor assignments. The default timeout is set for the robot drive.
+ */
+void RobotDrive::InitRobotDrive() {
+ m_frontLeftMotor = NULL;
+ m_frontRightMotor = NULL;
+ m_rearRightMotor = NULL;
+ m_rearLeftMotor = NULL;
+ m_sensitivity = 0.5;
+ m_maxOutput = 1.0;
+ m_safetyHelper = new MotorSafetyHelper(this);
+ m_safetyHelper->SetSafetyEnabled(true);
+}
+
+/** Constructor for RobotDrive with 2 motors specified with channel numbers.
+ * Set up parameters for a two wheel drive system where the
+ * left and right motor pwm channels are specified in the call.
+ * This call assumes Jaguars for controlling the motors.
+ * @param leftMotorChannel The PWM channel number on the default digital module that drives the left motor.
+ * @param rightMotorChannel The PWM channel number on the default digital module that drives the right motor.
+ */
+RobotDrive::RobotDrive(UINT32 leftMotorChannel, UINT32 rightMotorChannel)
+{
+ InitRobotDrive();
+ m_rearLeftMotor = new Jaguar(leftMotorChannel);
+ m_rearRightMotor = new Jaguar(rightMotorChannel);
+ for (INT32 i=0; i < kMaxNumberOfMotors; i++)
+ {
+ m_invertedMotors[i] = 1;
+ }
+ SetLeftRightMotorOutputs(0.0, 0.0);
+ m_deleteSpeedControllers = true;
+}
+
+/**
+ * Constructor for RobotDrive with 4 motors specified with channel numbers.
+ * Set up parameters for a four wheel drive system where all four motor
+ * pwm channels are specified in the call.
+ * This call assumes Jaguars for controlling the motors.
+ * @param frontLeftMotor Front left motor channel number on the default digital module
+ * @param rearLeftMotor Rear Left motor channel number on the default digital module
+ * @param frontRightMotor Front right motor channel number on the default digital module
+ * @param rearRightMotor Rear Right motor channel number on the default digital module
+ */
+RobotDrive::RobotDrive(UINT32 frontLeftMotor, UINT32 rearLeftMotor,
+ UINT32 frontRightMotor, UINT32 rearRightMotor)
+{
+ InitRobotDrive();
+ m_rearLeftMotor = new Jaguar(rearLeftMotor);
+ m_rearRightMotor = new Jaguar(rearRightMotor);
+ m_frontLeftMotor = new Jaguar(frontLeftMotor);
+ m_frontRightMotor = new Jaguar(frontRightMotor);
+ for (INT32 i=0; i < kMaxNumberOfMotors; i++)
+ {
+ m_invertedMotors[i] = 1;
+ }
+ SetLeftRightMotorOutputs(0.0, 0.0);
+ m_deleteSpeedControllers = true;
+}
+
+/**
+ * Constructor for RobotDrive with 2 motors specified as SpeedController objects.
+ * The SpeedController version of the constructor enables programs to use the RobotDrive classes with
+ * subclasses of the SpeedController objects, for example, versions with ramping or reshaping of
+ * the curve to suit motor bias or deadband elimination.
+ * @param leftMotor The left SpeedController object used to drive the robot.
+ * @param rightMotor the right SpeedController object used to drive the robot.
+ */
+RobotDrive::RobotDrive(SpeedController *leftMotor, SpeedController *rightMotor)
+{
+ InitRobotDrive();
+ if (leftMotor == NULL || rightMotor == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ m_rearLeftMotor = m_rearRightMotor = NULL;
+ return;
+ }
+ m_rearLeftMotor = leftMotor;
+ m_rearRightMotor = rightMotor;
+ for (INT32 i=0; i < kMaxNumberOfMotors; i++)
+ {
+ m_invertedMotors[i] = 1;
+ }
+ m_deleteSpeedControllers = false;
+}
+
+RobotDrive::RobotDrive(SpeedController &leftMotor, SpeedController &rightMotor)
+{
+ InitRobotDrive();
+ m_rearLeftMotor = &leftMotor;
+ m_rearRightMotor = &rightMotor;
+ for (INT32 i=0; i < kMaxNumberOfMotors; i++)
+ {
+ m_invertedMotors[i] = 1;
+ }
+ m_deleteSpeedControllers = false;
+}
+
+/**
+ * Constructor for RobotDrive with 4 motors specified as SpeedController objects.
+ * Speed controller input version of RobotDrive (see previous comments).
+ * @param rearLeftMotor The back left SpeedController object used to drive the robot.
+ * @param frontLeftMotor The front left SpeedController object used to drive the robot
+ * @param rearRightMotor The back right SpeedController object used to drive the robot.
+ * @param frontRightMotor The front right SpeedController object used to drive the robot.
+ */
+RobotDrive::RobotDrive(SpeedController *frontLeftMotor, SpeedController *rearLeftMotor,
+ SpeedController *frontRightMotor, SpeedController *rearRightMotor)
+{
+ InitRobotDrive();
+ if (frontLeftMotor == NULL || rearLeftMotor == NULL || frontRightMotor == NULL || rearRightMotor == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ return;
+ }
+ m_frontLeftMotor = frontLeftMotor;
+ m_rearLeftMotor = rearLeftMotor;
+ m_frontRightMotor = frontRightMotor;
+ m_rearRightMotor = rearRightMotor;
+ for (INT32 i=0; i < kMaxNumberOfMotors; i++)
+ {
+ m_invertedMotors[i] = 1;
+ }
+ m_deleteSpeedControllers = false;
+}
+
+RobotDrive::RobotDrive(SpeedController &frontLeftMotor, SpeedController &rearLeftMotor,
+ SpeedController &frontRightMotor, SpeedController &rearRightMotor)
+{
+ InitRobotDrive();
+ m_frontLeftMotor = &frontLeftMotor;
+ m_rearLeftMotor = &rearLeftMotor;
+ m_frontRightMotor = &frontRightMotor;
+ m_rearRightMotor = &rearRightMotor;
+ for (INT32 i=0; i < kMaxNumberOfMotors; i++)
+ {
+ m_invertedMotors[i] = 1;
+ }
+ m_deleteSpeedControllers = false;
+}
+
+/**
+ * RobotDrive destructor.
+ * Deletes motor objects that were not passed in and created internally only.
+ **/
+RobotDrive::~RobotDrive()
+{
+ if (m_deleteSpeedControllers)
+ {
+ delete m_frontLeftMotor;
+ delete m_rearLeftMotor;
+ delete m_frontRightMotor;
+ delete m_rearRightMotor;
+ }
+ delete m_safetyHelper;
+}
+
+/**
+ * Drive the motors at "speed" and "curve".
+ *
+ * The speed and curve are -1.0 to +1.0 values where 0.0 represents stopped and
+ * not turning. The algorithm for adding in the direction attempts to provide a constant
+ * turn radius for differing speeds.
+ *
+ * This function will most likely be used in an autonomous routine.
+ *
+ * @param outputMagnitude The forward component of the output magnitude to send to the motors.
+ * @param curve The rate of turn, constant for different forward speeds.
+ */
+void RobotDrive::Drive(float outputMagnitude, float curve)
+{
+ float leftOutput, rightOutput;
+ static bool reported = false;
+ if (!reported)
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_RobotDrive, GetNumMotors(), nUsageReporting::kRobotDrive_ArcadeRatioCurve);
+ reported = true;
+ }
+
+ if (curve < 0)
+ {
+ float value = log(-curve);
+ float ratio = (value - m_sensitivity)/(value + m_sensitivity);
+ if (ratio == 0) ratio =.0000000001;
+ leftOutput = outputMagnitude / ratio;
+ rightOutput = outputMagnitude;
+ }
+ else if (curve > 0)
+ {
+ float value = log(curve);
+ float ratio = (value - m_sensitivity)/(value + m_sensitivity);
+ if (ratio == 0) ratio =.0000000001;
+ leftOutput = outputMagnitude;
+ rightOutput = outputMagnitude / ratio;
+ }
+ else
+ {
+ leftOutput = outputMagnitude;
+ rightOutput = outputMagnitude;
+ }
+ SetLeftRightMotorOutputs(leftOutput, rightOutput);
+}
+
+/**
+ * Provide tank steering using the stored robot configuration.
+ * Drive the robot using two joystick inputs. The Y-axis will be selected from
+ * each Joystick object.
+ * @param leftStick The joystick to control the left side of the robot.
+ * @param rightStick The joystick to control the right side of the robot.
+ */
+void RobotDrive::TankDrive(GenericHID *leftStick, GenericHID *rightStick)
+{
+ if (leftStick == NULL || rightStick == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ return;
+ }
+ TankDrive(leftStick->GetY(), rightStick->GetY());
+}
+
+void RobotDrive::TankDrive(GenericHID &leftStick, GenericHID &rightStick)
+{
+ TankDrive(leftStick.GetY(), rightStick.GetY());
+}
+
+/**
+ * Provide tank steering using the stored robot configuration.
+ * This function lets you pick the axis to be used on each Joystick object for the left
+ * and right sides of the robot.
+ * @param leftStick The Joystick object to use for the left side of the robot.
+ * @param leftAxis The axis to select on the left side Joystick object.
+ * @param rightStick The Joystick object to use for the right side of the robot.
+ * @param rightAxis The axis to select on the right side Joystick object.
+ */
+void RobotDrive::TankDrive(GenericHID *leftStick, UINT32 leftAxis,
+ GenericHID *rightStick, UINT32 rightAxis)
+{
+ if (leftStick == NULL || rightStick == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ return;
+ }
+ TankDrive(leftStick->GetRawAxis(leftAxis), rightStick->GetRawAxis(rightAxis));
+}
+
+void RobotDrive::TankDrive(GenericHID &leftStick, UINT32 leftAxis,
+ GenericHID &rightStick, UINT32 rightAxis)
+{
+ TankDrive(leftStick.GetRawAxis(leftAxis), rightStick.GetRawAxis(rightAxis));
+}
+
+
+/**
+ * Provide tank steering using the stored robot configuration.
+ * This function lets you directly provide joystick values from any source.
+ * @param leftValue The value of the left stick.
+ * @param rightValue The value of the right stick.
+ */
+void RobotDrive::TankDrive(float leftValue, float rightValue)
+{
+ static bool reported = false;
+ if (!reported)
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_RobotDrive, GetNumMotors(), nUsageReporting::kRobotDrive_Tank);
+ reported = true;
+ }
+
+ // square the inputs (while preserving the sign) to increase fine control while permitting full power
+ leftValue = Limit(leftValue);
+ rightValue = Limit(rightValue);
+ if (leftValue >= 0.0)
+ {
+ leftValue = (leftValue * leftValue);
+ }
+ else
+ {
+ leftValue = -(leftValue * leftValue);
+ }
+ if (rightValue >= 0.0)
+ {
+ rightValue = (rightValue * rightValue);
+ }
+ else
+ {
+ rightValue = -(rightValue * rightValue);
+ }
+
+ SetLeftRightMotorOutputs(leftValue, rightValue);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * Given a single Joystick, the class assumes the Y axis for the move value and the X axis
+ * for the rotate value.
+ * (Should add more information here regarding the way that arcade drive works.)
+ * @param stick The joystick to use for Arcade single-stick driving. The Y-axis will be selected
+ * for forwards/backwards and the X-axis will be selected for rotation rate.
+ * @param squaredInputs If true, the sensitivity will be increased for small values
+ */
+void RobotDrive::ArcadeDrive(GenericHID *stick, bool squaredInputs)
+{
+ // simply call the full-featured ArcadeDrive with the appropriate values
+ ArcadeDrive(stick->GetY(), stick->GetX(), stick->GetTrigger());
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * Given a single Joystick, the class assumes the Y axis for the move value and the X axis
+ * for the rotate value.
+ * (Should add more information here regarding the way that arcade drive works.)
+ * @param stick The joystick to use for Arcade single-stick driving. The Y-axis will be selected
+ * for forwards/backwards and the X-axis will be selected for rotation rate.
+ * @param squaredInputs If true, the sensitivity will be increased for small values
+ */
+void RobotDrive::ArcadeDrive(GenericHID &stick, bool squaredInputs)
+{
+ // simply call the full-featured ArcadeDrive with the appropriate values
+ ArcadeDrive(stick.GetY(), stick.GetX(), stick.GetTrigger());
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * Given two joystick instances and two axis, compute the values to send to either two
+ * or four motors.
+ * @param moveStick The Joystick object that represents the forward/backward direction
+ * @param moveAxis The axis on the moveStick object to use for fowards/backwards (typically Y_AXIS)
+ * @param rotateStick The Joystick object that represents the rotation value
+ * @param rotateAxis The axis on the rotation object to use for the rotate right/left (typically X_AXIS)
+ * @param squaredInputs Setting this parameter to true increases the sensitivity at lower speeds
+ */
+void RobotDrive::ArcadeDrive(GenericHID* moveStick, UINT32 moveAxis,
+ GenericHID* rotateStick, UINT32 rotateAxis,
+ bool squaredInputs)
+{
+ float moveValue = moveStick->GetRawAxis(moveAxis);
+ float rotateValue = rotateStick->GetRawAxis(rotateAxis);
+
+ ArcadeDrive(moveValue, rotateValue, squaredInputs);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * Given two joystick instances and two axis, compute the values to send to either two
+ * or four motors.
+ * @param moveStick The Joystick object that represents the forward/backward direction
+ * @param moveAxis The axis on the moveStick object to use for fowards/backwards (typically Y_AXIS)
+ * @param rotateStick The Joystick object that represents the rotation value
+ * @param rotateAxis The axis on the rotation object to use for the rotate right/left (typically X_AXIS)
+ * @param squaredInputs Setting this parameter to true increases the sensitivity at lower speeds
+ */
+
+void RobotDrive::ArcadeDrive(GenericHID &moveStick, UINT32 moveAxis,
+ GenericHID &rotateStick, UINT32 rotateAxis,
+ bool squaredInputs)
+{
+ float moveValue = moveStick.GetRawAxis(moveAxis);
+ float rotateValue = rotateStick.GetRawAxis(rotateAxis);
+
+ ArcadeDrive(moveValue, rotateValue, squaredInputs);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * This function lets you directly provide joystick values from any source.
+ * @param moveValue The value to use for fowards/backwards
+ * @param rotateValue The value to use for the rotate right/left
+ * @param squaredInputs If set, increases the sensitivity at low speeds
+ */
+void RobotDrive::ArcadeDrive(float moveValue, float rotateValue, bool squaredInputs)
+{
+ static bool reported = false;
+ if (!reported)
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_RobotDrive, GetNumMotors(), nUsageReporting::kRobotDrive_ArcadeStandard);
+ reported = true;
+ }
+
+ // local variables to hold the computed PWM values for the motors
+ float leftMotorOutput;
+ float rightMotorOutput;
+
+ moveValue = Limit(moveValue);
+ rotateValue = Limit(rotateValue);
+
+ if (squaredInputs)
+ {
+ // square the inputs (while preserving the sign) to increase fine control while permitting full power
+ if (moveValue >= 0.0)
+ {
+ moveValue = (moveValue * moveValue);
+ }
+ else
+ {
+ moveValue = -(moveValue * moveValue);
+ }
+ if (rotateValue >= 0.0)
+ {
+ rotateValue = (rotateValue * rotateValue);
+ }
+ else
+ {
+ rotateValue = -(rotateValue * rotateValue);
+ }
+ }
+
+ if (moveValue > 0.0)
+ {
+ if (rotateValue > 0.0)
+ {
+ leftMotorOutput = moveValue - rotateValue;
+ rightMotorOutput = max(moveValue, rotateValue);
+ }
+ else
+ {
+ leftMotorOutput = max(moveValue, -rotateValue);
+ rightMotorOutput = moveValue + rotateValue;
+ }
+ }
+ else
+ {
+ if (rotateValue > 0.0)
+ {
+ leftMotorOutput = - max(-moveValue, rotateValue);
+ rightMotorOutput = moveValue + rotateValue;
+ }
+ else
+ {
+ leftMotorOutput = moveValue - rotateValue;
+ rightMotorOutput = - max(-moveValue, -rotateValue);
+ }
+ }
+ SetLeftRightMotorOutputs(leftMotorOutput, rightMotorOutput);
+}
+
+/**
+ * Drive method for Mecanum wheeled robots.
+ *
+ * A method for driving with Mecanum wheeled robots. There are 4 wheels
+ * on the robot, arranged so that the front and back wheels are toed in 45 degrees.
+ * When looking at the wheels from the top, the roller axles should form an X across the robot.
+ *
+ * This is designed to be directly driven by joystick axes.
+ *
+ * @param x The speed that the robot should drive in the X direction. [-1.0..1.0]
+ * @param y The speed that the robot should drive in the Y direction.
+ * This input is inverted to match the forward == -1.0 that joysticks produce. [-1.0..1.0]
+ * @param rotation The rate of rotation for the robot that is completely independent of
+ * the translation. [-1.0..1.0]
+ * @param gyroAngle The current angle reading from the gyro. Use this to implement field-oriented controls.
+ */
+void RobotDrive::MecanumDrive_Cartesian(float x, float y, float rotation, float gyroAngle)
+{
+ static bool reported = false;
+ if (!reported)
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_RobotDrive, GetNumMotors(), nUsageReporting::kRobotDrive_MecanumCartesian);
+ reported = true;
+ }
+
+ double xIn = x;
+ double yIn = y;
+ // Negate y for the joystick.
+ yIn = -yIn;
+ // Compenstate for gyro angle.
+ RotateVector(xIn, yIn, gyroAngle);
+
+ double wheelSpeeds[kMaxNumberOfMotors];
+ wheelSpeeds[kFrontLeftMotor] = xIn + yIn + rotation;
+ wheelSpeeds[kFrontRightMotor] = -xIn + yIn - rotation;
+ wheelSpeeds[kRearLeftMotor] = -xIn + yIn + rotation;
+ wheelSpeeds[kRearRightMotor] = xIn + yIn - rotation;
+
+ Normalize(wheelSpeeds);
+
+ UINT8 syncGroup = 0x80;
+
+ m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_invertedMotors[kFrontLeftMotor] * m_maxOutput, syncGroup);
+ m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_invertedMotors[kFrontRightMotor] * m_maxOutput, syncGroup);
+ m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_invertedMotors[kRearLeftMotor] * m_maxOutput, syncGroup);
+ m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup);
+
+ CANJaguar::UpdateSyncGroup(syncGroup);
+
+ m_safetyHelper->Feed();
+}
+
+/**
+ * Drive method for Mecanum wheeled robots.
+ *
+ * A method for driving with Mecanum wheeled robots. There are 4 wheels
+ * on the robot, arranged so that the front and back wheels are toed in 45 degrees.
+ * When looking at the wheels from the top, the roller axles should form an X across the robot.
+ *
+ * @param magnitude The speed that the robot should drive in a given direction. [-1.0..1.0]
+ * @param direction The direction the robot should drive in degrees. The direction and maginitute are
+ * independent of the rotation rate.
+ * @param rotation The rate of rotation for the robot that is completely independent of
+ * the magnitute or direction. [-1.0..1.0]
+ */
+void RobotDrive::MecanumDrive_Polar(float magnitude, float direction, float rotation)
+{
+ static bool reported = false;
+ if (!reported)
+ {
+ nUsageReporting::report(nUsageReporting::kResourceType_RobotDrive, GetNumMotors(), nUsageReporting::kRobotDrive_MecanumPolar);
+ reported = true;
+ }
+
+ // Normalized for full power along the Cartesian axes.
+ magnitude = Limit(magnitude) * sqrt(2.0);
+ // The rollers are at 45 degree angles.
+ double dirInRad = (direction + 45.0) * 3.14159 / 180.0;
+ double cosD = cos(dirInRad);
+ double sinD = sin(dirInRad);
+
+ double wheelSpeeds[kMaxNumberOfMotors];
+ wheelSpeeds[kFrontLeftMotor] = sinD * magnitude + rotation;
+ wheelSpeeds[kFrontRightMotor] = cosD * magnitude - rotation;
+ wheelSpeeds[kRearLeftMotor] = cosD * magnitude + rotation;
+ wheelSpeeds[kRearRightMotor] = sinD * magnitude - rotation;
+
+ Normalize(wheelSpeeds);
+
+ UINT8 syncGroup = 0x80;
+
+ m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_invertedMotors[kFrontLeftMotor] * m_maxOutput, syncGroup);
+ m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_invertedMotors[kFrontRightMotor] * m_maxOutput, syncGroup);
+ m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_invertedMotors[kRearLeftMotor] * m_maxOutput, syncGroup);
+ m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup);
+
+ CANJaguar::UpdateSyncGroup(syncGroup);
+
+ m_safetyHelper->Feed();
+}
+
+/**
+ * Holonomic Drive method for Mecanum wheeled robots.
+ *
+ * This is an alias to MecanumDrive_Polar() for backward compatability
+ *
+ * @param magnitude The speed that the robot should drive in a given direction. [-1.0..1.0]
+ * @param direction The direction the robot should drive. The direction and maginitute are
+ * independent of the rotation rate.
+ * @param rotation The rate of rotation for the robot that is completely independent of
+ * the magnitute or direction. [-1.0..1.0]
+ */
+void RobotDrive::HolonomicDrive(float magnitude, float direction, float rotation)
+{
+ MecanumDrive_Polar(magnitude, direction, rotation);
+}
+
+/** Set the speed of the right and left motors.
+ * This is used once an appropriate drive setup function is called such as
+ * TwoWheelDrive(). The motors are set to "leftOutput" and "rightOutput"
+ * and includes flipping the direction of one side for opposing motors.
+ * @param leftOutput The speed to send to the left side of the robot.
+ * @param rightOutput The speed to send to the right side of the robot.
+ */
+void RobotDrive::SetLeftRightMotorOutputs(float leftOutput, float rightOutput)
+{
+ wpi_assert(m_rearLeftMotor != NULL && m_rearRightMotor != NULL);
+
+ UINT8 syncGroup = 0x80;
+
+ if (m_frontLeftMotor != NULL)
+ m_frontLeftMotor->Set(Limit(leftOutput) * m_invertedMotors[kFrontLeftMotor] * m_maxOutput, syncGroup);
+ m_rearLeftMotor->Set(Limit(leftOutput) * m_invertedMotors[kRearLeftMotor] * m_maxOutput, syncGroup);
+
+ if (m_frontRightMotor != NULL)
+ m_frontRightMotor->Set(-Limit(rightOutput) * m_invertedMotors[kFrontRightMotor] * m_maxOutput, syncGroup);
+ m_rearRightMotor->Set(-Limit(rightOutput) * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup);
+
+ CANJaguar::UpdateSyncGroup(syncGroup);
+
+ m_safetyHelper->Feed();
+}
+
+/**
+ * Limit motor values to the -1.0 to +1.0 range.
+ */
+float RobotDrive::Limit(float num)
+{
+ if (num > 1.0)
+ {
+ return 1.0;
+ }
+ if (num < -1.0)
+ {
+ return -1.0;
+ }
+ return num;
+}
+
+/**
+ * Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
+ */
+void RobotDrive::Normalize(double *wheelSpeeds)
+{
+ double maxMagnitude = fabs(wheelSpeeds[0]);
+ INT32 i;
+ for (i=1; i<kMaxNumberOfMotors; i++)
+ {
+ double temp = fabs(wheelSpeeds[i]);
+ if (maxMagnitude < temp) maxMagnitude = temp;
+ }
+ if (maxMagnitude > 1.0)
+ {
+ for (i=0; i<kMaxNumberOfMotors; i++)
+ {
+ wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
+ }
+ }
+}
+
+/**
+ * Rotate a vector in Cartesian space.
+ */
+void RobotDrive::RotateVector(double &x, double &y, double angle)
+{
+ double cosA = cos(angle * (3.14159 / 180.0));
+ double sinA = sin(angle * (3.14159 / 180.0));
+ double xOut = x * cosA - y * sinA;
+ double yOut = x * sinA + y * cosA;
+ x = xOut;
+ y = yOut;
+}
+
+/*
+ * Invert a motor direction.
+ * This is used when a motor should run in the opposite direction as the drive
+ * code would normally run it. Motors that are direct drive would be inverted, the
+ * Drive code assumes that the motors are geared with one reversal.
+ * @param motor The motor index to invert.
+ * @param isInverted True if the motor should be inverted when operated.
+ */
+void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted)
+{
+ if (motor < 0 || motor > 3)
+ {
+ wpi_setWPIError(InvalidMotorIndex);
+ return;
+ }
+ m_invertedMotors[motor] = isInverted ? -1 : 1;
+}
+
+/**
+ * Set the turning sensitivity.
+ *
+ * This only impacts the Drive() entry-point.
+ * @param sensitivity Effectively sets the turning sensitivity (or turn radius for a given value)
+ */
+void RobotDrive::SetSensitivity(float sensitivity)
+{
+ m_sensitivity = sensitivity;
+}
+
+/**
+ * Configure the scaling factor for using RobotDrive with motor controllers in a mode other than PercentVbus.
+ * @param maxOutput Multiplied with the output percentage computed by the drive functions.
+ */
+void RobotDrive::SetMaxOutput(double maxOutput)
+{
+ m_maxOutput = maxOutput;
+}
+
+
+
+void RobotDrive::SetExpiration(float timeout)
+{
+ m_safetyHelper->SetExpiration(timeout);
+}
+
+float RobotDrive::GetExpiration()
+{
+ return m_safetyHelper->GetExpiration();
+}
+
+bool RobotDrive::IsAlive()
+{
+ return m_safetyHelper->IsAlive();
+}
+
+bool RobotDrive::IsSafetyEnabled()
+{
+ return m_safetyHelper->IsSafetyEnabled();
+}
+
+void RobotDrive::SetSafetyEnabled(bool enabled)
+{
+ m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+void RobotDrive::GetDescription(char *desc)
+{
+ sprintf(desc, "RobotDrive");
+}
+
+void RobotDrive::StopMotor()
+{
+ if (m_frontLeftMotor != NULL) m_frontLeftMotor->Disable();
+ if (m_frontRightMotor != NULL) m_frontRightMotor->Disable();
+ if (m_rearLeftMotor != NULL) m_rearLeftMotor->Disable();
+ if (m_rearRightMotor != NULL) m_rearRightMotor->Disable();
+}
diff --git a/aos/externals/WPILib/WPILib/RobotDrive.h b/aos/externals/WPILib/WPILib/RobotDrive.h
new file mode 100644
index 0000000..c3a045b
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/RobotDrive.h
@@ -0,0 +1,108 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef ROBOTDRIVE_H_
+#define ROBOTDRIVE_H_
+
+#include "ErrorBase.h"
+#include <stdlib.h>
+#include <vxWorks.h>
+#include "MotorSafety.h"
+#include "MotorSafetyHelper.h"
+
+class SpeedController;
+class GenericHID;
+
+/**
+ * Utility class for handling Robot drive based on a definition of the motor configuration.
+ * The robot drive class handles basic driving for a robot. Currently, 2 and 4 motor standard
+ * drive trains are supported. In the future other drive types like swerve and meccanum might
+ * be implemented. Motor channel numbers are passed supplied on creation of the class. Those are
+ * used for either the Drive function (intended for hand created drive code, such as autonomous)
+ * or with the Tank/Arcade functions intended to be used for Operator Control driving.
+ */
+class RobotDrive: public MotorSafety, public ErrorBase
+{
+public:
+ typedef enum
+ {
+ kFrontLeftMotor = 0,
+ kFrontRightMotor = 1,
+ kRearLeftMotor = 2,
+ kRearRightMotor = 3
+ } MotorType;
+
+ RobotDrive(UINT32 leftMotorChannel, UINT32 rightMotorChannel);
+ RobotDrive(UINT32 frontLeftMotorChannel, UINT32 rearLeftMotorChannel,
+ UINT32 frontRightMotorChannel, UINT32 rearRightMotorChannel);
+ RobotDrive(SpeedController *leftMotor, SpeedController *rightMotor);
+ RobotDrive(SpeedController &leftMotor, SpeedController &rightMotor);
+ RobotDrive(SpeedController *frontLeftMotor, SpeedController *rearLeftMotor,
+ SpeedController *frontRightMotor, SpeedController *rearRightMotor);
+ RobotDrive(SpeedController &frontLeftMotor, SpeedController &rearLeftMotor,
+ SpeedController &frontRightMotor, SpeedController &rearRightMotor);
+ virtual ~RobotDrive();
+
+ void Drive(float outputMagnitude, float curve);
+ void TankDrive(GenericHID *leftStick, GenericHID *rightStick);
+ void TankDrive(GenericHID &leftStick, GenericHID &rightStick);
+ void TankDrive(GenericHID *leftStick, UINT32 leftAxis, GenericHID *rightStick, UINT32 rightAxis);
+ void TankDrive(GenericHID &leftStick, UINT32 leftAxis, GenericHID &rightStick, UINT32 rightAxis);
+ void TankDrive(float leftValue, float rightValue);
+ void ArcadeDrive(GenericHID *stick, bool squaredInputs = true);
+ void ArcadeDrive(GenericHID &stick, bool squaredInputs = true);
+ void ArcadeDrive(GenericHID *moveStick, UINT32 moveChannel, GenericHID *rotateStick, UINT32 rotateChannel, bool squaredInputs = true);
+ void ArcadeDrive(GenericHID &moveStick, UINT32 moveChannel, GenericHID &rotateStick, UINT32 rotateChannel, bool squaredInputs = true);
+ void ArcadeDrive(float moveValue, float rotateValue, bool squaredInputs = true);
+ void MecanumDrive_Cartesian(float x, float y, float rotation, float gyroAngle = 0.0);
+ void MecanumDrive_Polar(float magnitude, float direction, float rotation);
+ void HolonomicDrive(float magnitude, float direction, float rotation);
+ virtual void SetLeftRightMotorOutputs(float leftOutput, float rightOutput);
+ void SetInvertedMotor(MotorType motor, bool isInverted);
+ void SetSensitivity(float sensitivity);
+ void SetMaxOutput(double maxOutput);
+
+ void SetExpiration(float timeout);
+ float GetExpiration();
+ bool IsAlive();
+ void StopMotor();
+ bool IsSafetyEnabled();
+ void SetSafetyEnabled(bool enabled);
+ void GetDescription(char *desc);
+
+protected:
+ void InitRobotDrive();
+ float Limit(float num);
+ void Normalize(double *wheelSpeeds);
+ void RotateVector(double &x, double &y, double angle);
+
+ static const INT32 kMaxNumberOfMotors = 4;
+
+ INT32 m_invertedMotors[kMaxNumberOfMotors];
+ float m_sensitivity;
+ double m_maxOutput;
+ bool m_deleteSpeedControllers;
+ SpeedController *m_frontLeftMotor;
+ SpeedController *m_frontRightMotor;
+ SpeedController *m_rearLeftMotor;
+ SpeedController *m_rearRightMotor;
+ MotorSafetyHelper *m_safetyHelper;
+
+private:
+ INT32 GetNumMotors()
+ {
+ int motors = 0;
+ if (m_frontLeftMotor) motors++;
+ if (m_frontRightMotor) motors++;
+ if (m_rearLeftMotor) motors++;
+ if (m_rearRightMotor) motors++;
+ return motors;
+ }
+ DISALLOW_COPY_AND_ASSIGN(RobotDrive);
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/SPI.cpp b/aos/externals/WPILib/WPILib/SPI.cpp
new file mode 100644
index 0000000..e7038f8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SPI.cpp
@@ -0,0 +1,528 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "SPI.h"
+
+#include "ChipObject/tSPI.h"
+#include "DigitalInput.h"
+#include "DigitalOutput.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Synchronized.h"
+#include "WPIErrors.h"
+
+#include <math.h>
+#include <usrLib.h>
+
+SEM_ID SPI::m_semaphore = NULL;
+
+/**
+ * Constructor for input and output.
+ *
+ * @param clk The digital output for the clock signal.
+ * @param mosi The digital output for the written data to the slave
+ * (master-out slave-in).
+ * @param miso The digital input for the input data from the slave
+ * (master-in slave-out).
+ */
+SPI::SPI(DigitalOutput &clk, DigitalOutput &mosi, DigitalInput &miso)
+{
+ Init(&clk, &mosi, &miso);
+}
+
+/**
+ * Constructor for input and output.
+ *
+ * @param clk The digital output for the clock signal.
+ * @param mosi The digital output for the written data to the slave
+ * (master-out slave-in).
+ * @param miso The digital input for the input data from the slave
+ * (master-in slave-out).
+ */
+SPI::SPI(DigitalOutput *clk, DigitalOutput *mosi, DigitalInput *miso)
+{
+ Init(clk, mosi, miso);
+}
+
+/**
+ * Constructor for output only.
+ *
+ * @param clk The digital output for the clock signal.
+ * @param mosi The digital output for the written data to the slave
+ * (master-out slave-in).
+ */
+SPI::SPI(DigitalOutput &clk, DigitalOutput &mosi)
+{
+ Init(&clk, &mosi, NULL);
+}
+
+/**
+ * Constructor for output only.
+ *
+ * @param clk The digital output for the clock signal.
+ * @param mosi The digital output for the written data to the slave
+ * (master-out slave-in).
+ */
+SPI::SPI(DigitalOutput *clk, DigitalOutput *mosi)
+{
+ Init(clk, mosi, NULL);
+}
+
+/**
+ * Constructor for input only.
+ *
+ * @param clk The digital output for the clock signal.
+ * @param miso The digital input for the input data from the slave
+ * (master-in slave-out).
+ */
+SPI::SPI(DigitalOutput &clk, DigitalInput &miso)
+{
+ Init(&clk, NULL, &miso);
+}
+
+/**
+ * Constructor for input only.
+ *
+ * @param clk The digital output for the clock signal.
+ * @param miso The digital input for the input data from the slave
+ * (master-in slave-out).
+ */
+SPI::SPI(DigitalOutput *clk, DigitalInput *miso)
+{
+ Init(clk, NULL, miso);
+}
+
+/**
+ * Destructor.
+ */
+SPI::~SPI()
+{
+ delete m_spi;
+}
+
+/**
+ * Initialize SPI channel configuration.
+ *
+ * @param clk The digital output for the clock signal.
+ * @param mosi The digital output for the written data to the slave
+ * (master-out slave-in).
+ * @param miso The digital input for the input data from the slave
+ * (master-in slave-out).
+ */
+void SPI::Init(DigitalOutput *clk, DigitalOutput *mosi, DigitalInput *miso)
+{
+ if (m_semaphore == NULL)
+ {
+ m_semaphore = semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+ }
+
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_spi = tSPI::create(&localStatus);
+ wpi_setError(localStatus);
+
+ m_config.BusBitWidth = 8;
+ m_config.ClockHalfPeriodDelay = 0;
+ m_config.MSBfirst = 0;
+ m_config.DataOnFalling = 0;
+ m_config.LatchFirst = 0;
+ m_config.LatchLast = 0;
+ m_config.FramePolarity = 0;
+ m_config.WriteOnly = miso ? 0 : 1;
+ m_config.ClockPolarity = 0;
+
+ m_channels.SCLK_Channel = clk->GetChannelForRouting();
+ m_channels.SCLK_Module = clk->GetModuleForRouting();
+ m_channels.SS_Channel = 0;
+ m_channels.SS_Module = 0;
+
+ if (mosi)
+ {
+ m_channels.MOSI_Channel = mosi->GetChannelForRouting();
+ m_channels.MOSI_Module = mosi->GetModuleForRouting();
+ }
+ else
+ {
+ m_channels.MOSI_Channel = 0;
+ m_channels.MOSI_Module = 0;
+ }
+
+ if (miso)
+ {
+ m_channels.MISO_Channel = miso->GetChannelForRouting();
+ m_channels.MISO_Module = miso->GetModuleForRouting();
+ }
+ else
+ {
+ m_channels.MISO_Channel = 0;
+ m_channels.MISO_Module = 0;
+ }
+
+ m_ss = NULL;
+
+ static INT32 instances = 0;
+ instances++;
+ nUsageReporting::report(nUsageReporting::kResourceType_SPI, instances);
+}
+
+/**
+ * Configure the number of bits from each word that the slave transmits
+ * or receives.
+ *
+ * @param bits The number of bits in one frame (1 to 32 bits).
+ */
+void SPI::SetBitsPerWord(UINT32 bits)
+{
+ m_config.BusBitWidth = bits;
+}
+
+/**
+ * Get the number of bits from each word that the slave transmits
+ * or receives.
+ *
+ * @return The number of bits in one frame (1 to 32 bits).
+ */
+UINT32 SPI::GetBitsPerWord()
+{
+ return m_config.BusBitWidth;
+}
+
+/**
+ * Configure the rate of the generated clock signal.
+ * The default and maximum value is 76,628.4 Hz.
+ *
+ * @param hz The clock rate in Hertz.
+ */
+void SPI::SetClockRate(double hz)
+{
+ int delay = 0;
+ // TODO: compute the appropriate values based on digital loop timing
+ if (hz <= 76628.4)
+ {
+ double v = (1.0/hz)/1.305e-5;
+ int intv = (int)v;
+ if (v-intv > 0.5)
+ delay = intv;
+ else
+ delay = intv-1;
+ }
+ if (delay > 255)
+ {
+ wpi_setWPIError(SPIClockRateTooLow);
+ delay = 255;
+ }
+ m_config.ClockHalfPeriodDelay = delay;
+}
+
+/**
+ * Configure the order that bits are sent and received on the wire
+ * to be most significant bit first.
+ */
+void SPI::SetMSBFirst()
+{
+ m_config.MSBfirst = 1;
+}
+
+/**
+ * Configure the order that bits are sent and received on the wire
+ * to be least significant bit first.
+ */
+void SPI::SetLSBFirst()
+{
+ m_config.MSBfirst = 0;
+}
+
+/**
+ * Configure that the data is stable on the falling edge and the data
+ * changes on the rising edge.
+ */
+void SPI::SetSampleDataOnFalling()
+{
+ m_config.DataOnFalling = 1;
+}
+
+/**
+ * Configure that the data is stable on the rising edge and the data
+ * changes on the falling edge.
+ */
+void SPI::SetSampleDataOnRising()
+{
+ m_config.DataOnFalling = 0;
+}
+
+/**
+ * Configure the slave select line behavior.
+ *
+ * @param ss slave select digital output.
+ * @param mode Frame mode:
+ * kChipSelect: active for the duration of the frame.
+ * kPreLatchPulse: pulses before the transfer of each frame.
+ * kPostLatchPulse: pulses after the transfer of each frame.
+ * kPreAndPostLatchPulse: pulses before and after each frame.
+ * @param activeLow True if slave select line is active low.
+ */
+void SPI::SetSlaveSelect(DigitalOutput *ss, tFrameMode mode, bool activeLow)
+{
+ if (ss)
+ {
+ m_channels.SS_Channel = ss->GetChannelForRouting();
+ m_channels.SS_Module = ss->GetModuleForRouting();
+ }
+ else
+ {
+ m_channels.SS_Channel = 0;
+ m_channels.SS_Module = 0;
+ }
+ m_ss = ss;
+
+ switch (mode)
+ {
+ case kChipSelect:
+ m_config.LatchFirst = 0;
+ m_config.LatchLast = 0;
+ break;
+ case kPreLatchPulse:
+ m_config.LatchFirst = 1;
+ m_config.LatchLast = 0;
+ break;
+ case kPostLatchPulse:
+ m_config.LatchFirst = 0;
+ m_config.LatchLast = 1;
+ break;
+ case kPreAndPostLatchPulse:
+ m_config.LatchFirst = 1;
+ m_config.LatchLast = 1;
+ break;
+ }
+
+ m_config.FramePolarity = activeLow ? 1 : 0;
+}
+
+/**
+ * Configure the slave select line behavior.
+ *
+ * @param ss slave select digital output.
+ * @param mode Frame mode:
+ * kChipSelect: active for the duration of the frame.
+ * kPreLatchPulse: pulses before the transfer of each frame.
+ * kPostLatchPulse: pulses after the transfer of each frame.
+ * kPreAndPostLatchPulse: pulses before and after each frame.
+ * @param activeLow True if slave select line is active low.
+ */
+void SPI::SetSlaveSelect(DigitalOutput &ss, tFrameMode mode, bool activeLow)
+{
+ SetSlaveSelect(&ss, mode, activeLow);
+}
+
+/**
+ * Get the slave select line behavior.
+ *
+ * @param mode Frame mode:
+ * kChipSelect: active for the duration of the frame.
+ * kPreLatchPulse: pulses before the transfer of each frame.
+ * kPostLatchPulse: pulses after the transfer of each frame.
+ * kPreAndPostLatchPulse: pulses before and after each frame.
+ * @param activeLow True if slave select line is active low.
+ * @return The slave select digital output.
+ */
+DigitalOutput *SPI::GetSlaveSelect(tFrameMode *mode, bool *activeLow)
+{
+ if (mode != NULL)
+ {
+ *mode = (tFrameMode) (m_config.LatchFirst | (m_config.LatchLast << 1));
+ }
+ if (activeLow != NULL)
+ {
+ *activeLow = m_config.FramePolarity != 0;
+ }
+ return m_ss;
+}
+
+/**
+ * Configure the clock output line to be active low.
+ * This is sometimes called clock polarity high.
+ */
+void SPI::SetClockActiveLow()
+{
+ m_config.ClockPolarity = 1;
+}
+
+/**
+ * Configure the clock output line to be active high.
+ * This is sometimes called clock polarity low.
+ */
+void SPI::SetClockActiveHigh()
+{
+ m_config.ClockPolarity = 0;
+}
+
+/**
+ * Apply configuration settings and reset the SPI logic.
+ */
+void SPI::ApplyConfig()
+{
+ Synchronized sync(m_semaphore);
+
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_spi->writeConfig(m_config, &localStatus);
+ m_spi->writeChannels(m_channels, &localStatus);
+ m_spi->strobeReset(&localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Get the number of words that can currently be stored before being
+ * transmitted to the device.
+ *
+ * @return The number of words available to be written.
+ */
+UINT16 SPI::GetOutputFIFOAvailable()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT16 result = m_spi->readAvailableToLoad(&localStatus);
+ wpi_setError(localStatus);
+ return result;
+}
+
+/**
+ * Get the number of words received and currently available to be read from
+ * the receive FIFO.
+ *
+ * @return The number of words available to read.
+ */
+UINT16 SPI::GetNumReceived()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT16 result = m_spi->readReceivedElements(&localStatus);
+ wpi_setError(localStatus);
+ return result;
+}
+
+/**
+ * Have all pending transfers completed?
+ *
+ * @return True if no transfers are pending.
+ */
+bool SPI::IsDone()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool result = m_spi->readStatus_Idle(&localStatus);
+ wpi_setError(localStatus);
+ return result;
+}
+
+/**
+ * Determine if the receive FIFO was full when attempting to add new data at
+ * end of a transfer.
+ *
+ * @return True if the receive FIFO overflowed.
+ */
+bool SPI::HadReceiveOverflow()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool result = m_spi->readStatus_ReceivedDataOverflow(&localStatus);
+ wpi_setError(localStatus);
+ return result;
+}
+
+/**
+ * Write a word to the slave device. Blocks until there is space in the
+ * output FIFO.
+ *
+ * If not running in output only mode, also saves the data received
+ * on the MISO input during the transfer into the receive FIFO.
+ */
+void SPI::Write(UINT32 data)
+{
+ if (m_channels.MOSI_Channel == 0 && m_channels.MOSI_Module == 0)
+ {
+ wpi_setWPIError(SPIWriteNoMOSI);
+ return;
+ }
+
+ Synchronized sync(m_semaphore);
+
+ while (GetOutputFIFOAvailable() == 0)
+ taskDelay(NO_WAIT);
+
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_spi->writeDataToLoad(data, &localStatus);
+ m_spi->strobeLoad(&localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Read a word from the receive FIFO.
+ *
+ * Waits for the current transfer to complete if the receive FIFO is empty.
+ *
+ * If the receive FIFO is empty, there is no active transfer, and initiate
+ * is false, errors.
+ *
+ * @param initiate If true, this function pushes "0" into the
+ * transmit buffer and initiates a transfer.
+ * If false, this function assumes that data is
+ * already in the receive FIFO from a previous write.
+ */
+UINT32 SPI::Read(bool initiate)
+{
+ if (m_channels.MISO_Channel == 0 && m_channels.MISO_Module == 0)
+ {
+ wpi_setWPIError(SPIReadNoMISO);
+ return 0;
+ }
+
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 data;
+ {
+ Synchronized sync(m_semaphore);
+
+ if (initiate)
+ {
+ m_spi->writeDataToLoad(0, &localStatus);
+ m_spi->strobeLoad(&localStatus);
+ }
+
+ // Do we have anything ready to read?
+ if (GetNumReceived() == 0)
+ {
+ if (!initiate && IsDone() && GetOutputFIFOAvailable() == kTransmitFIFODepth)
+ {
+ // Nothing to read: error out
+ wpi_setWPIError(SPIReadNoData);
+ return 0;
+ }
+
+ // Wait for the transaction to complete
+ while (GetNumReceived() == 0)
+ taskDelay(NO_WAIT);
+ }
+
+ m_spi->strobeReadReceivedData(&localStatus);
+ data = m_spi->readReceivedData(&localStatus);
+ }
+ wpi_setError(localStatus);
+
+ return data;
+}
+
+/**
+ * Stop any transfer in progress and empty the transmit FIFO.
+ */
+void SPI::Reset()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_spi->strobeReset(&localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Empty the receive FIFO.
+ */
+void SPI::ClearReceivedData()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_spi->strobeClearReceivedData(&localStatus);
+ wpi_setError(localStatus);
+}
diff --git a/aos/externals/WPILib/WPILib/SPI.h b/aos/externals/WPILib/WPILib/SPI.h
new file mode 100644
index 0000000..05f8a05
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SPI.h
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SPI_H__
+#define __SPI_H__
+
+#include "ChipObject.h"
+#include "SensorBase.h"
+
+class DigitalOutput;
+class DigitalInput;
+
+/**
+ * SPI bus interface class.
+ *
+ * This class is intended to be used by sensor (and other SPI device) drivers.
+ * It probably should not be used directly.
+ *
+ * The FPGA only supports a single SPI interface.
+ */
+class SPI : public SensorBase
+{
+public:
+ enum tFrameMode {kChipSelect, kPreLatchPulse, kPostLatchPulse, kPreAndPostLatchPulse};
+ enum tSPIConstants {kReceiveFIFODepth=512, kTransmitFIFODepth=512};
+
+ SPI(DigitalOutput &clk, DigitalOutput &mosi, DigitalInput &miso);
+ SPI(DigitalOutput *clk, DigitalOutput *mosi, DigitalInput *miso);
+ SPI(DigitalOutput &clk, DigitalOutput &mosi);
+ SPI(DigitalOutput *clk, DigitalOutput *mosi);
+ SPI(DigitalOutput &clk, DigitalInput &miso);
+ SPI(DigitalOutput *clk, DigitalInput *miso);
+ virtual ~SPI();
+
+ void SetBitsPerWord(UINT32 bits);
+ UINT32 GetBitsPerWord();
+ void SetClockRate(double hz);
+
+ void SetMSBFirst();
+ void SetLSBFirst();
+
+ void SetSampleDataOnFalling();
+ void SetSampleDataOnRising();
+
+ void SetSlaveSelect(DigitalOutput *ss, tFrameMode mode=kChipSelect, bool activeLow=false);
+ void SetSlaveSelect(DigitalOutput &ss, tFrameMode mode=kChipSelect, bool activeLow=false);
+ DigitalOutput *GetSlaveSelect(tFrameMode *mode=NULL, bool *activeLow=NULL);
+
+ void SetClockActiveLow();
+ void SetClockActiveHigh();
+
+ virtual void ApplyConfig();
+
+ virtual UINT16 GetOutputFIFOAvailable();
+ virtual UINT16 GetNumReceived();
+
+ virtual bool IsDone();
+ bool HadReceiveOverflow();
+
+ virtual void Write(UINT32 data);
+ virtual UINT32 Read(bool initiate = false);
+
+ virtual void Reset();
+ virtual void ClearReceivedData();
+
+protected:
+ static SEM_ID m_semaphore;
+
+ tSPI* m_spi;
+ tSPI::tConfig m_config;
+ tSPI::tChannels m_channels;
+ DigitalOutput *m_ss;
+
+private:
+ void Init(DigitalOutput *clk, DigitalOutput *mosi, DigitalInput *miso);
+
+ DISALLOW_COPY_AND_ASSIGN(SPI);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/SafePWM.cpp b/aos/externals/WPILib/WPILib/SafePWM.cpp
new file mode 100644
index 0000000..484fbe6
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SafePWM.cpp
@@ -0,0 +1,117 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "SafePWM.h"
+
+#include "MotorSafetyHelper.h"
+
+/**
+ * Initialize a SafePWM object by setting defaults
+ */
+void SafePWM::InitSafePWM()
+{
+ m_safetyHelper = new MotorSafetyHelper(this);
+ m_safetyHelper->SetSafetyEnabled(false);
+}
+
+/**
+ * Constructor for a SafePWM object taking a channel number
+ * @param channel The channel number to be used for the underlying PWM object
+ */
+SafePWM::SafePWM(UINT32 channel): PWM(channel)
+{
+ InitSafePWM();
+}
+
+/**
+ * Constructor for a SafePWM object taking channel and slot numbers.
+ * @param moduleNumber The digital module (1 or 2).
+ * @param channel The PWM channel number on the module (1..10).
+ */
+SafePWM::SafePWM(UINT8 moduleNumber, UINT32 channel): PWM(moduleNumber, channel)
+{
+ InitSafePWM();
+}
+
+SafePWM::~SafePWM()
+{
+ delete m_safetyHelper;
+}
+
+/*
+ * Set the expiration time for the PWM object
+ * @param timeout The timeout (in seconds) for this motor object
+ */
+void SafePWM::SetExpiration(float timeout)
+{
+ m_safetyHelper->SetExpiration(timeout);
+}
+
+/**
+ * Return the expiration time for the PWM object.
+ * @returns The expiration time value.
+ */
+float SafePWM::GetExpiration()
+{
+ return m_safetyHelper->GetExpiration();
+}
+
+/**
+ * Check if the PWM object is currently alive or stopped due to a timeout.
+ * @returns a bool value that is true if the motor has NOT timed out and should still
+ * be running.
+ */
+bool SafePWM::IsAlive()
+{
+ return m_safetyHelper->IsAlive();
+}
+
+/**
+ * Stop the motor associated with this PWM object.
+ * This is called by the MotorSafetyHelper object when it has a timeout for this PWM and needs to
+ * stop it from running.
+ */
+void SafePWM::StopMotor()
+{
+ SetRaw(kPwmDisabled);
+}
+
+/**
+ * Enable/disable motor safety for this device
+ * Turn on and off the motor safety option for this PWM object.
+ * @param enabled True if motor safety is enforced for this object
+ */
+void SafePWM::SetSafetyEnabled(bool enabled)
+{
+ m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+/**
+ * Check if motor safety is enabled for this object
+ * @returns True if motor safety is enforced for this object
+ */
+bool SafePWM::IsSafetyEnabled()
+{
+ return m_safetyHelper->IsSafetyEnabled();
+}
+
+void SafePWM::GetDescription(char *desc)
+{
+ sprintf(desc, "PWM %d on module %d", GetChannel(), GetModuleNumber());
+}
+
+/**
+ * Feed the MotorSafety timer when setting the speed.
+ * This method is called by the subclass motor whenever it updates its speed, thereby reseting
+ * the timeout value.
+ * @param speed Value to pass to the PWM class
+ */
+void SafePWM::SetSpeed(float speed)
+{
+ PWM::SetSpeed(speed);
+ m_safetyHelper->Feed();
+}
+
diff --git a/aos/externals/WPILib/WPILib/SafePWM.h b/aos/externals/WPILib/WPILib/SafePWM.h
new file mode 100644
index 0000000..feef64c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SafePWM.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SAFE_PWM__
+#define __SAFE_PWM__
+
+#include "MotorSafety.h"
+#include "PWM.h"
+
+class MotorSafetyHelper;
+
+/**
+ * A safe version of the PWM class.
+ * It is safe because it implements the MotorSafety interface that provides timeouts
+ * in the event that the motor value is not updated before the expiration time.
+ * This delegates the actual work to a MotorSafetyHelper object that is used for all
+ * objects that implement MotorSafety.
+ */
+class SafePWM: public PWM, public MotorSafety
+{
+public:
+ explicit SafePWM(UINT32 channel);
+ SafePWM(UINT8 moduleNumber, UINT32 channel);
+ ~SafePWM();
+
+ void SetExpiration(float timeout);
+ float GetExpiration();
+ bool IsAlive();
+ void StopMotor();
+ bool IsSafetyEnabled();
+ void SetSafetyEnabled(bool enabled);
+ void GetDescription(char *desc);
+
+ virtual void SetSpeed(float speed);
+private:
+ void InitSafePWM();
+ MotorSafetyHelper *m_safetyHelper;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Scripts/CopyWPILibToUpdateDirectory.cmd b/aos/externals/WPILib/WPILib/Scripts/CopyWPILibToUpdateDirectory.cmd
new file mode 100644
index 0000000..e397e2a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Scripts/CopyWPILibToUpdateDirectory.cmd
@@ -0,0 +1,48 @@
+
+C:
+
+mkdir \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib\Buttons
+mkdir \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib\CAN
+mkdir \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib\ChipObject
+mkdir \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib\CInterfaces
+mkdir \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib\Commands
+mkdir \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib\NetworkCommunication
+mkdir \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib\NetworkTables
+mkdir \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib\SmartDashboard
+mkdir \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib\visa
+mkdir \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib\Vision
+mkdir \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib\Vision2009
+
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\*.h
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\Buttons\*.h
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\CAN\*.h
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\ChipObject\*.h
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\CInterfaces\*.h
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\Commands\*.h
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\NetworkCommunication\*.h
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\NetworkTables\*.h
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\SmartDashboard\*.h
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\visa\*.h
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\Vision\*.h
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPIlib\Vision2009\*.h
+
+del \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\lib\WPILib.a
+
+cd \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\h\WPILib
+
+copy \WindRiver\workspace\WPILib\*.h
+copy \WindRiver\workspace\WPILib\Buttons\*.h Buttons
+copy \WindRiver\workspace\WPILib\CAN\*.h CAN
+copy \WindRiver\workspace\WPILib\ChipObject\*.h ChipObject
+copy \WindRiver\workspace\WPILib\CInterfaces\*.h CInterfaces
+copy \WindRiver\workspace\WPILib\Commands\*.h Commands
+copy \WindRiver\workspace\WPILib\NetworkCommunication\*.h NetworkCommunication
+copy \WindRiver\workspace\WPILib\NetworkTables\*.h NetworkTables
+copy \WindRiver\workspace\WPILib\SmartDashboard\*.h SmartDashboard
+copy \WindRiver\workspace\WPILib\visa\*.h visa
+copy \WindRiver\workspace\WPILib\Vision\*.h Vision
+copy \WindRiver\workspace\WPILib\Vision2009\*.h Vision2009
+
+copy C:\WindRiver\workspace\WPILib\PPC603gnu\WPILib\Debug\WPILib.a \WindRiver\workspace\WorkbenchUpdate\vxworks-6.3\target\lib
+
+cd \WindRiver\workspace\WPILib\Scripts
diff --git a/aos/externals/WPILib/WPILib/Scripts/Makefile b/aos/externals/WPILib/WPILib/Scripts/Makefile
new file mode 100644
index 0000000..bc19164
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Scripts/Makefile
@@ -0,0 +1,2184 @@
+# Wind River Workbench generated Makefile.
+# Do not edit!!!
+#
+# The file ".wrmakefile" is the template used by the Wind River Workbench to
+# generate the makefiles of this project. Add user-specific build targets and
+# make rules only(!) in this project's ".wrmakefile" file. These will then be
+# automatically dumped into the makefiles.
+
+WIND_HOME := $(subst \,/,$(WIND_HOME))
+WIND_BASE := $(subst \,/,$(WIND_BASE))
+WIND_USR := $(subst \,/,$(WIND_USR))
+
+all : pre_build main_all post_build
+
+_clean ::
+ @echo "make: removing targets and objects of `pwd`"
+
+TRACE=0
+TRACEON=$(TRACE:0=@)
+TRACE_FLAG=$(TRACEON:1=)
+
+MAKEFILE := Makefile
+
+BUILD_SPEC = PPC603gnu
+DEBUG_MODE = 1
+SRC_DIR := .
+BUILD_ROOT_DIR :=
+PRJ_ROOT_DIR := C:/windriver/workspace/WPILib
+WS_ROOT_DIR := C:/windriver/workspace
+
+ALL_BUILD_SPECS := PPC32diab PPC32gnu PPC32sfdiab PPC32sfgnu \
+ PPC403diab PPC403gnu PPC405diab PPC405gnu \
+ PPC405sfdiab PPC405sfgnu PPC440diab PPC440gnu \
+ PPC440sfdiab PPC440sfgnu PPC603diab PPC603gnu \
+ PPC604diab PPC604gnu PPC85XXdiab PPC85XXgnu \
+ PPC85XXsfdiab PPC85XXsfgnu PPC860sfdiab PPC860sfgnu \
+ SIMLINUXdiab SIMLINUXgnu SIMNTdiab SIMNTgnu \
+ SIMSPARCSOLARISdiab SIMSPARCSOLARISgnu
+ENABLED_BUILD_SPECS := PPC603gnu
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32diab_DEBUG
+else
+OBJ_DIR := PPC32diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32gnu_DEBUG
+else
+OBJ_DIR := PPC32gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfdiab_DEBUG
+else
+OBJ_DIR := PPC32sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfgnu_DEBUG
+else
+OBJ_DIR := PPC32sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403diab_DEBUG
+else
+OBJ_DIR := PPC403diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403gnu_DEBUG
+else
+OBJ_DIR := PPC403gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405diab_DEBUG
+else
+OBJ_DIR := PPC405diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405gnu_DEBUG
+else
+OBJ_DIR := PPC405gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfdiab_DEBUG
+else
+OBJ_DIR := PPC405sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfgnu_DEBUG
+else
+OBJ_DIR := PPC405sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440diab_DEBUG
+else
+OBJ_DIR := PPC440diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440gnu_DEBUG
+else
+OBJ_DIR := PPC440gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfdiab_DEBUG
+else
+OBJ_DIR := PPC440sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfgnu_DEBUG
+else
+OBJ_DIR := PPC440sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603diab_DEBUG
+else
+OBJ_DIR := PPC603diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603gnu_DEBUG
+else
+OBJ_DIR := PPC603gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604diab_DEBUG
+else
+OBJ_DIR := PPC604diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604gnu_DEBUG
+else
+OBJ_DIR := PPC604gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXdiab_DEBUG
+else
+OBJ_DIR := PPC85XXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXgnu_DEBUG
+else
+OBJ_DIR := PPC85XXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfdiab_DEBUG
+else
+OBJ_DIR := PPC85XXsfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfgnu_DEBUG
+else
+OBJ_DIR := PPC85XXsfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfdiab_DEBUG
+else
+OBJ_DIR := PPC860sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfgnu_DEBUG
+else
+OBJ_DIR := PPC860sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXdiab_DEBUG
+else
+OBJ_DIR := SIMLINUXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXgnu_DEBUG
+else
+OBJ_DIR := SIMLINUXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTdiab_DEBUG
+else
+OBJ_DIR := SIMNTdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTgnu_DEBUG
+else
+OBJ_DIR := SIMNTgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISdiab_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISgnu_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISgnu
+endif
+endif
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+
+PROJECT_TYPE = DKM
+DEFINES =
+EXPAND_DBG = 0
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFH:vxworks63 -Xstmw-slow -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mhard-float -mstrict-align -mno-implicit-fp -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -msoft-float -mstrict-align
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC403FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=403 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC603FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=603 -mstrict-align -mno-implicit-fp -mlongcall
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I.. -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC604FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=604 -mstrict-align -mno-implicit-fp
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC860FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=860 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tSPARCFH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC =
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+
+
+
+
+
+-include $(PRJ_ROOT_DIR)/*.makefile
+
+-include *.makefile
+
+main_all : external_build $(PROJECT_TARGETS)
+ @echo "make: built targets of `pwd`"
+
+# entry point for extending the build
+external_build ::
+ @echo ""
+
+# main entry point for pre processing prior to the build
+pre_build :: $(PRE_BUILD_STEP) generate_sources
+ @echo ""
+
+# entry point for generating sources prior to the build
+generate_sources ::
+ @echo ""
+
+# main entry point for post processing after the build
+post_build :: $(POST_BUILD_STEP) deploy_output
+ @echo ""
+
+# entry point for deploying output after the build
+deploy_output ::
+ @echo ""
+
+clean :: external_clean $(CLEAN_STEP) _clean
+
+# entry point for extending the build clean
+external_clean ::
+ @echo ""
diff --git a/aos/externals/WPILib/WPILib/Scripts/updateBuiltInLibrary.cmd b/aos/externals/WPILib/WPILib/Scripts/updateBuiltInLibrary.cmd
new file mode 100644
index 0000000..6c06802
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Scripts/updateBuiltInLibrary.cmd
@@ -0,0 +1,46 @@
+cd C:\WindRiver\vxworks-6.3\target
+
+mkdir h\WPILib
+mkdir h\WPILib\Buttons
+mkdir h\WPILib\CAN
+mkdir h\WPILib\ChipObject
+mkdir h\WPILib\CInterfaces
+mkdir h\WPILib\Commands
+mkdir h\WPILib\NetworkCommunication
+mkdir h\WPILib\NetworkTables
+mkdir h\WPILib\SmartDashboard
+mkdir h\WPILib\visa
+mkdir h\WPILib\Vision
+mkdir h\WPILib\Vision2009
+
+del h\WPILib\*.h
+del h\WPILib\Buttons\*.h
+del h\WPILib\CAN\*.h
+del h\WPILib\ChipObject\*.h
+del h\WPILib\CInterfaces\*.h
+del h\WPILib\Commands\*.h
+del h\WPILib\NetworkCommunication\*.h
+del h\WPILib\NetworkTables\*.h
+del h\WPILib\SmartDashboard\*.h
+del h\WPILib\visa\*.h
+del h\WPILib\Vision\*.h
+del h\WPILib\Vision2009\*.h
+
+copy c:\WindRiver\workspace\WPILib\*.h h\WPILib
+copy c:\WindRiver\workspace\WPILib\Buttons\*.h h\WPILib\Buttons
+copy c:\WindRiver\workspace\WPILib\CAN\*.h h\WPILib\CAN
+copy c:\WindRiver\workspace\WPILib\ChipObject\*.h h\WPILib\ChipObject
+copy C:\WindRiver\workspace\WPILib\CInterfaces\*.h h\WPILib\CInterfaces
+copy C:\WindRiver\workspace\WPILib\Commands\*.h h\WPILib\Commands
+copy C:\WindRiver\workspace\WPILib\NetworkCommunication\*.h h\WPILib\NetworkCommunication
+copy C:\WindRiver\workspace\WPILib\NetworkTables\*.h h\WPILib\NetworkTables
+copy C:\WindRiver\workspace\WPILib\SmartDashboard\*.h h\WPILib\SmartDashboard
+copy c:\WindRiver\workspace\WPILib\visa\*.h h\WPILib\visa
+copy c:\WindRiver\workspace\WPILib\Vision\*.h h\WPILib\Vision
+copy c:\WindRiver\workspace\WPILib\Vision2009\*.h h\WPILib\Vision2009
+
+copy C:\WindRiver\workspace\WPILib\PPC603gnu\WPILib\Debug\WPILib.a lib
+
+rem copy c:\WindRiver\workspace\WorkbenchUpdate\frc_20*.zip c:\WindRiver\WPILib\cRIO_Images
+
+cd \WindRiver\workspace\WPILib\Scripts
diff --git a/aos/externals/WPILib/WPILib/SensorBase.cpp b/aos/externals/WPILib/WPILib/SensorBase.cpp
new file mode 100644
index 0000000..a68d260
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SensorBase.cpp
@@ -0,0 +1,192 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "SensorBase.h"
+
+#include "NetworkCommunication/LoadOut.h"
+#include "WPIErrors.h"
+
+const UINT32 SensorBase::kSystemClockTicksPerMicrosecond;
+const UINT32 SensorBase::kDigitalChannels;
+const UINT32 SensorBase::kAnalogChannels;
+const UINT32 SensorBase::kAnalogModules;
+const UINT32 SensorBase::kDigitalModules;
+const UINT32 SensorBase::kSolenoidChannels;
+const UINT32 SensorBase::kSolenoidModules;
+const UINT32 SensorBase::kPwmChannels;
+const UINT32 SensorBase::kRelayChannels;
+const UINT32 SensorBase::kChassisSlots;
+SensorBase *SensorBase::m_singletonList = NULL;
+
+/**
+ * Creates an instance of the sensor base and gets an FPGA handle
+ */
+SensorBase::SensorBase()
+{
+}
+
+/**
+ * Frees the resources for a SensorBase.
+ */
+SensorBase::~SensorBase()
+{
+}
+
+/**
+ * Add sensor to the singleton list.
+ * Add this sensor to the list of singletons that need to be deleted when
+ * the robot program exits. Each of the sensors on this list are singletons,
+ * that is they aren't allocated directly with new, but instead are allocated
+ * by the static GetInstance method. As a result, they are never deleted when
+ * the program exits. Consequently these sensors may still be holding onto
+ * resources and need to have their destructors called at the end of the program.
+ */
+void SensorBase::AddToSingletonList()
+{
+ m_nextSingleton = m_singletonList;
+ m_singletonList = this;
+}
+
+/**
+ * Delete all the singleton classes on the list.
+ * All the classes that were allocated as singletons need to be deleted so
+ * their resources can be freed.
+ */
+void SensorBase::DeleteSingletons()
+{
+ for (SensorBase *next = m_singletonList; next != NULL;)
+ {
+ SensorBase *tmp = next;
+ next = next->m_nextSingleton;
+ delete tmp;
+ }
+ m_singletonList = NULL;
+}
+
+/**
+ * Check that the analog module number is valid.
+ *
+ * @return Analog module is valid and present
+ */
+bool SensorBase::CheckAnalogModule(UINT8 moduleNumber)
+{
+ if (nLoadOut::getModulePresence(nLoadOut::kModuleType_Analog, moduleNumber - 1))
+ return true;
+ return false;
+}
+
+/**
+ * Check that the digital module number is valid.
+ *
+ * @return Digital module is valid and present
+ */
+bool SensorBase::CheckDigitalModule(UINT8 moduleNumber)
+{
+ if (nLoadOut::getModulePresence(nLoadOut::kModuleType_Digital, moduleNumber - 1))
+ return true;
+ return false;
+}
+
+/**
+ * Check that the digital module number is valid.
+ *
+ * @return Digital module is valid and present
+ */
+bool SensorBase::CheckPWMModule(UINT8 moduleNumber)
+{
+ return CheckDigitalModule(moduleNumber);
+}
+
+/**
+ * Check that the digital module number is valid.
+ *
+ * @return Digital module is valid and present
+ */
+bool SensorBase::CheckRelayModule(UINT8 moduleNumber)
+{
+ return CheckDigitalModule(moduleNumber);
+}
+
+/**
+ * Check that the solenoid module number is valid.
+ *
+ * @return Solenoid module is valid and present
+ */
+bool SensorBase::CheckSolenoidModule(UINT8 moduleNumber)
+{
+ if (nLoadOut::getModulePresence(nLoadOut::kModuleType_Solenoid, moduleNumber - 1))
+ return true;
+ return false;
+}
+
+/**
+ * Check that the digital channel number is valid.
+ * Verify that the channel number is one of the legal channel numbers. Channel numbers are
+ * 1-based.
+ *
+ * @return Digital channel is valid
+ */
+bool SensorBase::CheckDigitalChannel(UINT32 channel)
+{
+ if (channel > 0 && channel <= kDigitalChannels)
+ return true;
+ return false;
+}
+
+/**
+ * Check that the digital channel number is valid.
+ * Verify that the channel number is one of the legal channel numbers. Channel numbers are
+ * 1-based.
+ *
+ * @return Relay channel is valid
+ */
+bool SensorBase::CheckRelayChannel(UINT32 channel)
+{
+ if (channel > 0 && channel <= kRelayChannels)
+ return true;
+ return false;
+}
+
+/**
+ * Check that the digital channel number is valid.
+ * Verify that the channel number is one of the legal channel numbers. Channel numbers are
+ * 1-based.
+ *
+ * @return PWM channel is valid
+ */
+bool SensorBase::CheckPWMChannel(UINT32 channel)
+{
+ if (channel > 0 && channel <= kPwmChannels)
+ return true;
+ return false;
+}
+
+/**
+ * Check that the analog channel number is value.
+ * Verify that the analog channel number is one of the legal channel numbers. Channel numbers
+ * are 1-based.
+ *
+ * @return Analog channel is valid
+ */
+bool SensorBase::CheckAnalogChannel(UINT32 channel)
+{
+ if (channel > 0 && channel <= kAnalogChannels)
+ return true;
+ return false;
+}
+
+/**
+ * Verify that the solenoid channel number is within limits.
+ *
+ * @return Solenoid channel is valid
+ */
+bool SensorBase::CheckSolenoidChannel(UINT32 channel)
+{
+ if (channel > 0 && channel <= kSolenoidChannels)
+ return true;
+ return false;
+}
+
diff --git a/aos/externals/WPILib/WPILib/SensorBase.h b/aos/externals/WPILib/WPILib/SensorBase.h
new file mode 100644
index 0000000..1b149b1
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SensorBase.h
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef SENSORBASE_H_
+#define SENSORBASE_H_
+
+#include "ChipObject/NiRio.h"
+#include "ErrorBase.h"
+#include <stdio.h>
+#include "Base.h"
+
+/**
+ * Base class for all sensors.
+ * Stores most recent status information as well as containing utility functions for checking
+ * channels and error processing.
+ */
+class SensorBase: public ErrorBase {
+public:
+ SensorBase();
+ virtual ~SensorBase();
+ static void DeleteSingletons();
+ static UINT32 GetDefaultAnalogModule() { return 1; }
+ static UINT32 GetDefaultDigitalModule() { return 1; }
+ static UINT32 GetDefaultSolenoidModule() { return 1; }
+ static bool CheckAnalogModule(UINT8 moduleNumber);
+ static bool CheckDigitalModule(UINT8 moduleNumber);
+ static bool CheckPWMModule(UINT8 moduleNumber);
+ static bool CheckRelayModule(UINT8 moduleNumber);
+ static bool CheckSolenoidModule(UINT8 moduleNumber);
+ static bool CheckDigitalChannel(UINT32 channel);
+ static bool CheckRelayChannel(UINT32 channel);
+ static bool CheckPWMChannel(UINT32 channel);
+ static bool CheckAnalogChannel(UINT32 channel);
+ static bool CheckSolenoidChannel(UINT32 channel);
+
+ static const UINT32 kSystemClockTicksPerMicrosecond = 40;
+ static const UINT32 kDigitalChannels = 14;
+ static const UINT32 kAnalogChannels = 8;
+ static const UINT32 kAnalogModules = 2;
+ static const UINT32 kDigitalModules = 2;
+ static const UINT32 kSolenoidChannels = 8;
+ static const UINT32 kSolenoidModules = 2;
+ static const UINT32 kPwmChannels = 10;
+ static const UINT32 kRelayChannels = 8;
+ static const UINT32 kChassisSlots = 8;
+protected:
+ void AddToSingletonList();
+
+private:
+ DISALLOW_COPY_AND_ASSIGN(SensorBase);
+ static SensorBase *m_singletonList;
+ SensorBase *m_nextSingleton;
+};
+
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/SerialPort.cpp b/aos/externals/WPILib/WPILib/SerialPort.cpp
new file mode 100644
index 0000000..f161016
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SerialPort.cpp
@@ -0,0 +1,331 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "SerialPort.h"
+
+#include "NetworkCommunication/UsageReporting.h"
+#include "visa/visa.h"
+
+//static ViStatus _VI_FUNCH ioCompleteHandler (ViSession vi, ViEventType eventType, ViEvent event, ViAddr userHandle);
+
+/**
+ * Create an instance of a Serial Port class.
+ *
+ * @param baudRate The baud rate to configure the serial port. The cRIO-9074 supports up to 230400 Baud.
+ * @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
+ * @param parity Select the type of parity checking to use.
+ * @param stopBits The number of stop bits to use as defined by the enum StopBits.
+ */
+SerialPort::SerialPort(UINT32 baudRate, UINT8 dataBits, SerialPort::Parity parity, SerialPort::StopBits stopBits)
+ : m_resourceManagerHandle (0)
+ , m_portHandle (0)
+ , m_consoleModeEnabled (false)
+{
+ ViStatus localStatus = VI_SUCCESS;
+ localStatus = viOpenDefaultRM((ViSession*)&m_resourceManagerHandle);
+ wpi_setError(localStatus);
+
+ localStatus = viOpen(m_resourceManagerHandle, "ASRL1::INSTR", VI_NULL, VI_NULL, (ViSession*)&m_portHandle);
+ wpi_setError(localStatus);
+ if (localStatus != 0)
+ {
+ m_consoleModeEnabled = true;
+ return;
+ }
+
+ localStatus = viSetAttribute(m_portHandle, VI_ATTR_ASRL_BAUD, baudRate);
+ wpi_setError(localStatus);
+ localStatus = viSetAttribute(m_portHandle, VI_ATTR_ASRL_DATA_BITS, dataBits);
+ wpi_setError(localStatus);
+ localStatus = viSetAttribute(m_portHandle, VI_ATTR_ASRL_PARITY, parity);
+ wpi_setError(localStatus);
+ localStatus = viSetAttribute(m_portHandle, VI_ATTR_ASRL_STOP_BITS, stopBits);
+ wpi_setError(localStatus);
+
+ // Set the default timeout to 5 seconds.
+ SetTimeout(5.0f);
+
+ // Don't wait until the buffer is full to transmit.
+ SetWriteBufferMode(kFlushOnAccess);
+
+ EnableTermination();
+
+ //viInstallHandler(m_portHandle, VI_EVENT_IO_COMPLETION, ioCompleteHandler, this);
+ //viEnableEvent(m_portHandle, VI_EVENT_IO_COMPLETION, VI_HNDLR, VI_NULL);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_SerialPort, 0);
+}
+
+/**
+ * Destructor.
+ */
+SerialPort::~SerialPort()
+{
+ if (!m_consoleModeEnabled)
+ {
+ //viUninstallHandler(m_portHandle, VI_EVENT_IO_COMPLETION, ioCompleteHandler, this);
+ viClose(m_portHandle);
+ }
+ viClose(m_resourceManagerHandle);
+}
+
+/**
+ * Set the type of flow control to enable on this port.
+ *
+ * By default, flow control is disabled.
+ */
+void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl)
+{
+ if (!m_consoleModeEnabled)
+ {
+ ViStatus localStatus = viSetAttribute (m_portHandle, VI_ATTR_ASRL_FLOW_CNTRL, flowControl);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Enable termination and specify the termination character.
+ *
+ * Termination is currently only implemented for receive.
+ * When the the terminator is recieved, the Read() or Scanf() will return
+ * fewer bytes than requested, stopping after the terminator.
+ *
+ * @param terminator The character to use for termination.
+ */
+void SerialPort::EnableTermination(char terminator)
+{
+ if (!m_consoleModeEnabled)
+ {
+ viSetAttribute(m_portHandle, VI_ATTR_TERMCHAR_EN, VI_TRUE);
+ viSetAttribute(m_portHandle, VI_ATTR_TERMCHAR, terminator);
+ viSetAttribute(m_portHandle, VI_ATTR_ASRL_END_IN, VI_ASRL_END_TERMCHAR);
+ }
+}
+
+/**
+ * Disable termination behavior.
+ */
+void SerialPort::DisableTermination()
+{
+ if (!m_consoleModeEnabled)
+ {
+ viSetAttribute(m_portHandle, VI_ATTR_TERMCHAR_EN, VI_FALSE);
+ viSetAttribute(m_portHandle, VI_ATTR_ASRL_END_IN, VI_ASRL_END_NONE);
+ }
+}
+
+/**
+ * Get the number of bytes currently available to read from the serial port.
+ *
+ * @return The number of bytes available to read.
+ */
+INT32 SerialPort::GetBytesReceived()
+{
+ INT32 bytes = 0;
+ if (!m_consoleModeEnabled)
+ {
+ ViStatus localStatus = viGetAttribute(m_portHandle, VI_ATTR_ASRL_AVAIL_NUM, &bytes);
+ wpi_setError(localStatus);
+ }
+ return bytes;
+}
+
+/**
+ * Output formatted text to the serial port.
+ *
+ * @bug All pointer-based parameters seem to return an error.
+ *
+ * @param writeFmt A string that defines the format of the output.
+ */
+void SerialPort::Printf(const char *writeFmt, ...)
+{
+ if (!m_consoleModeEnabled)
+ {
+ va_list args;
+ va_start (args, writeFmt);
+ ViStatus localStatus = viVPrintf(m_portHandle, (ViString)writeFmt, args);
+ va_end (args);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Input formatted text from the serial port.
+ *
+ * @bug All pointer-based parameters seem to return an error.
+ *
+ * @param readFmt A string that defines the format of the input.
+ */
+void SerialPort::Scanf(const char *readFmt, ...)
+{
+ if (!m_consoleModeEnabled)
+ {
+ va_list args;
+ va_start (args, readFmt);
+ ViStatus localStatus = viVScanf(m_portHandle, (ViString)readFmt, args);
+ va_end (args);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Read raw bytes out of the buffer.
+ *
+ * @param buffer Pointer to the buffer to store the bytes in.
+ * @param count The maximum number of bytes to read.
+ * @return The number of bytes actually read into the buffer.
+ */
+UINT32 SerialPort::Read(char *buffer, INT32 count)
+{
+ UINT32 retCount = 0;
+ if (!m_consoleModeEnabled)
+ {
+ ViStatus localStatus = viBufRead(m_portHandle, (ViPBuf)buffer, count, (ViPUInt32)&retCount);
+ switch (localStatus)
+ {
+ case VI_SUCCESS_TERM_CHAR:
+ case VI_SUCCESS_MAX_CNT:
+ case VI_ERROR_TMO: // Timeout
+ break;
+ default:
+ wpi_setError(localStatus);
+ }
+ }
+ return retCount;
+}
+
+/**
+ * Write raw bytes to the buffer.
+ *
+ * @param buffer Pointer to the buffer to read the bytes from.
+ * @param count The maximum number of bytes to write.
+ * @return The number of bytes actually written into the port.
+ */
+UINT32 SerialPort::Write(const char *buffer, INT32 count)
+{
+ UINT32 retCount = 0;
+ if (!m_consoleModeEnabled)
+ {
+ ViStatus localStatus = viBufWrite(m_portHandle, (ViPBuf)buffer, count, (ViPUInt32)&retCount);
+ wpi_setError(localStatus);
+ }
+ return retCount;
+}
+
+/**
+ * Configure the timeout of the serial port.
+ *
+ * This defines the timeout for transactions with the hardware.
+ * It will affect reads and very large writes.
+ *
+ * @param timeout The number of seconds to to wait for I/O.
+ */
+void SerialPort::SetTimeout(float timeout)
+{
+ if (!m_consoleModeEnabled)
+ {
+ ViStatus localStatus = viSetAttribute(m_portHandle, VI_ATTR_TMO_VALUE, (UINT32)(timeout * 1e3));
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Specify the size of the input buffer.
+ *
+ * Specify the amount of data that can be stored before data
+ * from the device is returned to Read or Scanf. If you want
+ * data that is recieved to be returned immediately, set this to 1.
+ *
+ * It the buffer is not filled before the read timeout expires, all
+ * data that has been received so far will be returned.
+ *
+ * @param size The read buffer size.
+ */
+void SerialPort::SetReadBufferSize(UINT32 size)
+{
+ if (!m_consoleModeEnabled)
+ {
+ ViStatus localStatus = viSetBuf(m_portHandle, VI_READ_BUF, size);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Specify the size of the output buffer.
+ *
+ * Specify the amount of data that can be stored before being
+ * transmitted to the device.
+ *
+ * @param size The write buffer size.
+ */
+void SerialPort::SetWriteBufferSize(UINT32 size)
+{
+ if (!m_consoleModeEnabled)
+ {
+ ViStatus localStatus = viSetBuf(m_portHandle, VI_WRITE_BUF, size);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Specify the flushing behavior of the output buffer.
+ *
+ * When set to kFlushOnAccess, data is synchronously written to the serial port
+ * after each call to either Printf() or Write().
+ *
+ * When set to kFlushWhenFull, data will only be written to the serial port when
+ * the buffer is full or when Flush() is called.
+ *
+ * @param mode The write buffer mode.
+ */
+void SerialPort::SetWriteBufferMode(SerialPort::WriteBufferMode mode)
+{
+ if (!m_consoleModeEnabled)
+ {
+ ViStatus localStatus = viSetAttribute(m_portHandle, VI_ATTR_WR_BUF_OPER_MODE, mode);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Force the output buffer to be written to the port.
+ *
+ * This is used when SetWriteBufferMode() is set to kFlushWhenFull to force a
+ * flush before the buffer is full.
+ */
+void SerialPort::Flush()
+{
+ if (!m_consoleModeEnabled)
+ {
+ ViStatus localStatus = viFlush(m_portHandle, VI_WRITE_BUF);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Reset the serial port driver to a known state.
+ *
+ * Empty the transmit and receive buffers in the device and formatted I/O.
+ */
+void SerialPort::Reset()
+{
+ if (!m_consoleModeEnabled)
+ {
+ ViStatus localStatus = viClear(m_portHandle);
+ wpi_setError(localStatus);
+ }
+}
+
+//void SerialPort::_internalHandler(UINT32 port, UINT32 eventType, UINT32 event)
+//{
+//}
+
+//ViStatus _VI_FUNCH ioCompleteHandler (ViSession vi, ViEventType eventType, ViEvent event, ViAddr userHandle)
+//{
+// ((SerialPort*) userHandle)->_internalHandler(vi, eventType, event);
+// return VI_SUCCESS;
+//}
+
diff --git a/aos/externals/WPILib/WPILib/SerialPort.h b/aos/externals/WPILib/WPILib/SerialPort.h
new file mode 100644
index 0000000..fbff896
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SerialPort.h
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SerialPort_h__
+#define __SerialPort_h__
+
+#include "ErrorBase.h"
+#include <vxWorks.h>
+
+/**
+ * Driver for the RS-232 serial port on the cRIO.
+ *
+ * The current implementation uses the VISA formatted I/O mode. This means that
+ * all traffic goes through the fomatted buffers. This allows the intermingled
+ * use of Printf(), Scanf(), and the raw buffer accessors Read() and Write().
+ *
+ * More information can be found in the NI-VISA User Manual here:
+ * http://www.ni.com/pdf/manuals/370423a.pdf
+ * and the NI-VISA Programmer's Reference Manual here:
+ * http://www.ni.com/pdf/manuals/370132c.pdf
+ */
+class SerialPort : public ErrorBase
+{
+public:
+ typedef enum {kParity_None=0, kParity_Odd=1, kParity_Even=2, kParity_Mark=3, kParity_Space=4} Parity;
+ typedef enum {kStopBits_One=10, kStopBits_OnePointFive=15, kStopBits_Two=20} StopBits;
+ typedef enum {kFlowControl_None=0, kFlowControl_XonXoff=1, kFlowControl_RtsCts=2, kFlowControl_DtrDsr=4} FlowControl;
+ typedef enum {kFlushOnAccess=1, kFlushWhenFull=2} WriteBufferMode;
+
+ SerialPort(UINT32 baudRate, UINT8 dataBits = 8, Parity parity = kParity_None, StopBits stopBits = kStopBits_One);
+ ~SerialPort();
+ void SetFlowControl(FlowControl flowControl);
+ void EnableTermination(char terminator = '\n');
+ void DisableTermination();
+ INT32 GetBytesReceived();
+ void Printf(const char *writeFmt, ...);
+ void Scanf(const char *readFmt, ...);
+ UINT32 Read(char *buffer, INT32 count);
+ UINT32 Write(const char *buffer, INT32 count);
+ void SetTimeout(float timeout);
+ void SetReadBufferSize(UINT32 size);
+ void SetWriteBufferSize(UINT32 size);
+ void SetWriteBufferMode(WriteBufferMode mode);
+ void Flush();
+ void Reset();
+
+ /*
+ * Do not call me!
+ */
+ //void _internalHandler(UINT32 port, UINT32 eventType, UINT32 event);
+private:
+ UINT32 m_resourceManagerHandle;
+ UINT32 m_portHandle;
+ bool m_consoleModeEnabled;
+ DISALLOW_COPY_AND_ASSIGN(SerialPort);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Servo.cpp b/aos/externals/WPILib/WPILib/Servo.cpp
new file mode 100644
index 0000000..fb00224
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Servo.cpp
@@ -0,0 +1,121 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Servo.h"
+
+#include "NetworkCommunication/UsageReporting.h"
+
+const float Servo::kMaxServoAngle;
+const float Servo::kMinServoAngle;
+
+/**
+ * Common initialization code called by all constructors.
+ *
+ * InitServo() assigns defaults for the period multiplier for the servo PWM control signal, as
+ * well as the minimum and maximum PWM values supported by the servo.
+ */
+void Servo::InitServo()
+{
+ // TODO: compute the appropriate values based on digital loop timing
+ SetBounds(245, 0, 0, 0, 11);
+ SetPeriodMultiplier(kPeriodMultiplier_4X);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Servo, GetChannel(), GetModuleNumber() - 1);
+}
+
+/**
+ * Constructor that assumes the default digital module.
+ *
+ * @param channel The PWM channel on the digital module to which the servo is attached.
+ */
+Servo::Servo(UINT32 channel) : SafePWM(channel)
+{
+ InitServo();
+}
+
+/**
+ * Constructor that specifies the digital module.
+ *
+ * @param moduleNumber The digital module (1 or 2).
+ * @param channel The PWM channel on the digital module to which the servo is attached (1..10).
+ */
+Servo::Servo(UINT8 moduleNumber, UINT32 channel) : SafePWM(moduleNumber, channel)
+{
+ InitServo();
+}
+
+Servo::~Servo()
+{
+}
+
+/**
+ * Set the servo position.
+ *
+ * Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
+ *
+ * @param value Position from 0.0 to 1.0.
+ */
+void Servo::Set(float value)
+{
+ SetPosition(value);
+}
+
+/**
+ * Set the servo to offline.
+ *
+ * Set the servo raw value to 0 (undriven)
+ */
+void Servo::SetOffline() {
+ SetRaw(0);
+}
+
+/**
+ * Get the servo position.
+ *
+ * Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
+ *
+ * @return Position from 0.0 to 1.0.
+ */
+float Servo::Get()
+{
+ return GetPosition();
+}
+
+/**
+ * Set the servo angle.
+ *
+ * Assume that the servo angle is linear with respect to the PWM value (big assumption, need to test).
+ *
+ * Servo angles that are out of the supported range of the servo simply "saturate" in that direction
+ * In other words, if the servo has a range of (X degrees to Y degrees) than angles of less than X
+ * result in an angle of X being set and angles of more than Y degrees result in an angle of Y being set.
+ *
+ * @param degrees The angle in degrees to set the servo.
+ */
+void Servo::SetAngle(float degrees)
+{
+ if (degrees < kMinServoAngle)
+ {
+ degrees = kMinServoAngle;
+ }
+ else if (degrees > kMaxServoAngle)
+ {
+ degrees = kMaxServoAngle;
+ }
+
+ SetPosition(((float) (degrees - kMinServoAngle)) / GetServoAngleRange());
+}
+
+/**
+ * Get the servo angle.
+ *
+ * Assume that the servo angle is linear with respect to the PWM value (big assumption, need to test).
+ * @return The angle in degrees to which the servo is set.
+ */
+float Servo::GetAngle()
+{
+ return (float)GetPosition() * GetServoAngleRange() + kMinServoAngle;
+}
diff --git a/aos/externals/WPILib/WPILib/Servo.h b/aos/externals/WPILib/WPILib/Servo.h
new file mode 100644
index 0000000..70123a6
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Servo.h
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef SERVO_H
+#define SERVO_H
+
+#include "SafePWM.h"
+#include "SpeedController.h"
+
+/**
+ * Standard hobby style servo.
+ *
+ * The range parameters default to the appropriate values for the Hitec HS-322HD servo provided
+ * in the FIRST Kit of Parts in 2008.
+ */
+class Servo : public SafePWM
+{
+public:
+ explicit Servo(UINT32 channel);
+ Servo(UINT8 moduleNumber, UINT32 channel);
+ virtual ~Servo();
+ void Set(float value);
+ void SetOffline();
+ float Get();
+ void SetAngle(float angle);
+ float GetAngle();
+ static float GetMaxAngle() { return kMaxServoAngle; };
+ static float GetMinAngle() { return kMinServoAngle; };
+
+private:
+ void InitServo();
+ float GetServoAngleRange() {return kMaxServoAngle - kMinServoAngle;}
+
+ static const float kMaxServoAngle = 170.0;
+ static const float kMinServoAngle = 0.0;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/SimpleRobot.cpp b/aos/externals/WPILib/WPILib/SimpleRobot.cpp
new file mode 100644
index 0000000..8860aa9
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SimpleRobot.cpp
@@ -0,0 +1,120 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "SimpleRobot.h"
+
+#include "DriverStation.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Timer.h"
+
+SimpleRobot::SimpleRobot()
+ : m_robotMainOverridden (true)
+{
+ m_watchdog.SetEnabled(false);
+}
+
+/**
+ * Robot-wide initialization code should go here.
+ *
+ * Programmers should override this method for default Robot-wide initialization which will
+ * be called when the robot is first powered on. It will be called exactly 1 time.
+ */
+void SimpleRobot::RobotInit()
+{
+ printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Disabled should go here.
+ * Programmers should override this method to run code that should run while the field is
+ * disabled.
+ */
+void SimpleRobot::Disabled()
+{
+ printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Autonomous should go here.
+ * Programmers should override this method to run code that should run while the field is
+ * in the autonomous period.
+ */
+void SimpleRobot::Autonomous()
+{
+ printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Operator control (tele-operated) code should go here.
+ * Programmers should override this method to run code that should run while the field is
+ * in the Operator Control (tele-operated) period.
+ */
+void SimpleRobot::OperatorControl()
+{
+ printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Robot main program for free-form programs.
+ *
+ * This should be overridden by user subclasses if the intent is to not use the Autonomous() and
+ * OperatorControl() methods. In that case, the program is responsible for sensing when to run
+ * the autonomous and operator control functions in their program.
+ *
+ * This method will be called immediately after the constructor is called. If it has not been
+ * overridden by a user subclass (i.e. the default version runs), then the Autonomous() and
+ * OperatorControl() methods will be called.
+ */
+void SimpleRobot::RobotMain()
+{
+ m_robotMainOverridden = false;
+}
+
+/**
+ * Start a competition.
+ * This code needs to track the order of the field starting to ensure that everything happens
+ * in the right order. Repeatedly run the correct method, either Autonomous or OperatorControl
+ * when the robot is enabled. After running the correct method, wait for some state to change,
+ * either the other mode starts or the robot is disabled. Then go back and wait for the robot
+ * to be enabled again.
+ */
+void SimpleRobot::StartCompetition()
+{
+ nUsageReporting::report(nUsageReporting::kResourceType_Framework, nUsageReporting::kFramework_Simple);
+
+ RobotMain();
+
+ if (!m_robotMainOverridden)
+ {
+ // first and one-time initialization
+ RobotInit();
+
+ while (true)
+ {
+ if (IsDisabled())
+ {
+ m_ds->InDisabled(true);
+ Disabled();
+ m_ds->InDisabled(false);
+ while (IsDisabled()) m_ds->WaitForData();
+ }
+ else if (IsAutonomous())
+ {
+ m_ds->InAutonomous(true);
+ Autonomous();
+ m_ds->InAutonomous(false);
+ while (IsAutonomous() && IsEnabled()) m_ds->WaitForData();
+ }
+ else
+ {
+ m_ds->InOperatorControl(true);
+ OperatorControl();
+ m_ds->InOperatorControl(false);
+ while (IsOperatorControl() && IsEnabled()) m_ds->WaitForData();
+ }
+ }
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/SimpleRobot.h b/aos/externals/WPILib/WPILib/SimpleRobot.h
new file mode 100644
index 0000000..ac282fa
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SimpleRobot.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef SIMPLE_ROBOT_H
+#define SIMPLE_ROBOT_H
+
+#include "RobotBase.h"
+
+/**
+ * @todo If this is going to last until release, it needs a better name.
+ */
+class SimpleRobot: public RobotBase
+{
+public:
+ SimpleRobot();
+ virtual ~SimpleRobot() {}
+ virtual void RobotInit();
+ virtual void Disabled();
+ virtual void Autonomous();
+ virtual void OperatorControl();
+ virtual void RobotMain();
+ void StartCompetition();
+
+private:
+ bool m_robotMainOverridden;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Skeleton.h b/aos/externals/WPILib/WPILib/Skeleton.h
new file mode 100644
index 0000000..be15767
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Skeleton.h
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SKELETON_H__
+#define __SKELETON_H__
+
+/**
+ * Represents Skeleton data from a Kinect device connected to the
+ * Driver Station. See Getting Started with Microsoft Kinect for
+ * FRC and the Kinect for Windows SDK API reference for more information
+ */
+class Skeleton
+{
+ friend class Kinect;
+public:
+ typedef enum
+ {
+ HipCenter = 0,
+ Spine = 1,
+ ShoulderCenter = 2,
+ Head = 3,
+ ShoulderLeft = 4,
+ ElbowLeft = 5,
+ WristLeft = 6,
+ HandLeft = 7,
+ ShoulderRight = 8,
+ ElbowRight = 9,
+ WristRight = 10,
+ HandRight = 11,
+ HipLeft = 12,
+ KneeLeft = 13,
+ AnkleLeft = 14,
+ FootLeft = 15,
+ HipRight = 16,
+ KneeRight = 17,
+ AnkleRight = 18,
+ FootRight = 19,
+ JointCount = 20
+ } JointTypes;
+
+ typedef enum {kNotTracked, kInferred, kTracked} JointTrackingState;
+
+ typedef struct
+ {
+ float x;
+ float y;
+ float z;
+ JointTrackingState trackingState;
+ } Joint;
+
+ Joint GetHandRight() { return m_joints[HandRight]; }
+ Joint GetHandLeft() { return m_joints[HandLeft]; }
+ Joint GetWristRight() { return m_joints[WristRight]; }
+ Joint GetWristLeft() { return m_joints[WristLeft]; }
+ Joint GetElbowLeft() { return m_joints[ElbowLeft]; }
+ Joint GetElbowRight() { return m_joints[ElbowRight]; }
+ Joint GetShoulderLeft() { return m_joints[ShoulderLeft]; }
+ Joint GetShoulderRight() { return m_joints[ShoulderRight]; }
+ Joint GetShoulderCenter() { return m_joints[ShoulderCenter]; }
+ Joint GetHead() { return m_joints[Head]; }
+ Joint GetSpine() { return m_joints[Spine]; }
+ Joint GetHipCenter() { return m_joints[HipCenter]; }
+ Joint GetHipRight() { return m_joints[HipRight]; }
+ Joint GetHipLeft() { return m_joints[HipLeft]; }
+ Joint GetKneeLeft() { return m_joints[KneeLeft]; }
+ Joint GetKneeRight() { return m_joints[KneeRight]; }
+ Joint GetAnkleLeft() { return m_joints[AnkleLeft]; }
+ Joint GetAnkleRight() { return m_joints[AnkleRight]; }
+ Joint GetFootLeft() { return m_joints[FootLeft]; }
+ Joint GetFootRight() { return m_joints[FootRight]; }
+ Joint GetJointValue(JointTypes index) { return m_joints[index]; }
+
+private:
+ Joint m_joints[20];
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/SmartDashboard/SendableChooser.cpp b/aos/externals/WPILib/WPILib/SmartDashboard/SendableChooser.cpp
new file mode 100644
index 0000000..ed3990a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SmartDashboard/SendableChooser.cpp
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "SmartDashboard/SendableChooser.h"
+
+#include "NetworkTables/NetworkTable.h"
+#include <stdio.h>
+
+static const char *kDefault = "default";
+static const char *kCount = "count";
+static const char *kSelected = "selected";
+
+SendableChooser::SendableChooser()
+{
+ m_table = new NetworkTable();
+ m_count = 0;
+}
+
+/**
+ * Adds the given object to the list of options. On the {@link SmartDashboard} on the desktop,
+ * the object will appear as the given name.
+ * @param name the name of the option
+ * @param object the option
+ */
+void SendableChooser::AddObject(const char *name, void *object)
+{
+ std::pair<std::map<std::string, void *>::iterator, bool> ret = m_choices.insert(std::pair<std::string, void *>(name, object));
+ if (ret.second)
+ {
+ //idBuf is: 10 bytes for m_count and 1 for NULL term
+ char idBuf[11];
+ snprintf(idBuf, 11, "%d", m_count);
+ m_ids.insert(std::pair<void *, std::string>(object, idBuf));
+ m_table->PutString(idBuf, name);
+ m_count++;
+ m_table->PutInt(kCount, m_count);
+ }
+ else
+ {
+ std::string id = m_ids[ret.first->second];
+ ret.first->second = object;
+ m_table->PutString(id, name);
+ }
+}
+
+/**
+ * Add the given object to the list of options and marks it as the default.
+ * Functionally, this is very close to {@link SendableChooser#AddObject(const char *name, void *object) AddObject(...)}
+ * except that it will use this as the default option if none other is explicitly selected.
+ * @param name the name of the option
+ * @param object the option
+ */
+void SendableChooser::AddDefault(const char *name, void *object)
+{
+ m_defaultChoice = object;
+ AddObject(name, object);
+ m_table->PutString(kDefault, name);
+}
+
+/**
+ * Returns the selected option. If there is none selected, it will return the default. If there is none selected
+ * and no default, then it will return {@code NULL}.
+ * @return the option selected
+ */
+void *SendableChooser::GetSelected()
+{
+ return m_table->ContainsKey(kSelected) ? m_choices[m_table->GetString(kSelected)] : m_defaultChoice;
+}
diff --git a/aos/externals/WPILib/WPILib/SmartDashboard/SendableChooser.h b/aos/externals/WPILib/WPILib/SmartDashboard/SendableChooser.h
new file mode 100644
index 0000000..d25dca0
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SmartDashboard/SendableChooser.h
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SENDABLE_CHOOSER_H__
+#define __SENDABLE_CHOOSER_H__
+
+#include "SmartDashboard/SmartDashboardData.h"
+#include <map>
+#include <string>
+
+class NetworkTable;
+
+/**
+ * The {@link SendableChooser} class is a useful tool for presenting a selection of options
+ * to the {@link SmartDashboard}.
+ *
+ * <p>For instance, you may wish to be able to select between multiple autonomous modes.
+ * You can do this by putting every possible {@link Command} you want to run as an autonomous into
+ * a {@link SendableChooser} and then put it into the {@link SmartDashboard} to have a list of options
+ * appear on the laptop. Once autonomous starts, simply ask the {@link SendableChooser} what the selected
+ * value is.</p>
+ *
+ * @see SmartDashboard
+ */
+class SendableChooser : public SmartDashboardData
+{
+public:
+ SendableChooser();
+ virtual ~SendableChooser() {};
+
+ void AddObject(const char *name, void *object);
+ void AddDefault(const char *name, void *object);
+ void *GetSelected();
+
+ // SmartDashboardData interface
+ virtual std::string GetType() {return "String Chooser";}
+ virtual NetworkTable *GetTable() {return m_table;}
+
+private:
+ void *m_defaultChoice;
+ std::map<std::string, void *> m_choices;
+ std::map<void *, std::string> m_ids;
+ NetworkTable *m_table;
+ int m_count;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/SmartDashboard/SendableGyro.cpp b/aos/externals/WPILib/WPILib/SmartDashboard/SendableGyro.cpp
new file mode 100644
index 0000000..fd694a4
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SmartDashboard/SendableGyro.cpp
@@ -0,0 +1,157 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "SmartDashboard/SendableGyro.h"
+
+#include "NetworkTables/NetworkTable.h"
+#include "WPIErrors.h"
+
+#include <taskLib.h>
+
+/** The time (in seconds) between updates to the table */
+static const double kDefaultTimeBetweenUpdates = 0.2;
+static const char *kAngle = "angle";
+
+/**
+ * Gyro constructor given a moduleNumber and a channel.
+ *
+ * @param moduleNumber The analog module the gyro is connected to.
+ * @param channel The analog channel the gyro is connected to.
+ */
+SendableGyro::SendableGyro(UINT8 moduleNumber, UINT32 channel) :
+ Gyro(moduleNumber, channel),
+ m_offset(0.0),
+ m_period(kDefaultTimeBetweenUpdates),
+ m_table(NULL),
+ m_publisher("SendableGyroPublisher", (FUNCPTR)InitPublishTask),
+ m_runPublisher(false)
+{
+}
+
+/**
+ * Gyro constructor with only a channel.
+ *
+ * Use the default analog module slot.
+ *
+ * @param channel The analog channel the gyro is connected to.
+ */
+SendableGyro::SendableGyro(UINT32 channel) :
+ Gyro(channel),
+ m_offset(0.0),
+ m_period(kDefaultTimeBetweenUpdates),
+ m_table(NULL),
+ m_publisher("SendableGyroPublisher", (FUNCPTR)InitPublishTask),
+ m_runPublisher(false)
+{
+}
+
+/**
+ * Gyro constructor with a precreated analog channel object.
+ * Use this constructor when the analog channel needs to be shared. There
+ * is no reference counting when an AnalogChannel is passed to the gyro.
+ * @param channel The AnalogChannel object that the gyro is connected to.
+ */
+SendableGyro::SendableGyro(AnalogChannel* channel):
+ Gyro(channel),
+ m_offset(0.0),
+ m_period(kDefaultTimeBetweenUpdates),
+ m_table(NULL),
+ m_publisher("SendableGyroPublisher", (FUNCPTR)InitPublishTask),
+ m_runPublisher(false)
+{
+}
+
+SendableGyro::~SendableGyro()
+{
+ if (m_table != NULL)
+ {
+ // Stop the task
+ m_runPublisher = false;
+ while(m_publisher.Verify())
+ taskDelay(10);
+
+ // Stop listening to the table
+ m_table->RemoveChangeListener(kAngle, this);
+
+ delete m_table;
+ m_table = NULL;
+ }
+}
+
+float SendableGyro::GetAngle()
+{
+ return m_offset + Gyro::GetAngle();
+}
+
+void SendableGyro::Reset()
+{
+ m_offset = 0.0;
+ Gyro::Reset();
+}
+
+/**
+ * Sets the time (in seconds) between updates to the {@link SmartDashboard}.
+ * The default is 0.2 seconds.
+ * @param period the new time between updates
+ */
+void SendableGyro::SetUpdatePeriod(double period)
+{
+ if (period <= 0.0)
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "period <= 0.0");
+ else
+ m_period = period;
+}
+
+/**
+ * Returns the period (in seconds) between updates to the {@link SmartDashboard}.
+ * This value is independent of whether or not this {@link SendableGyro} is connected
+ * to the {@link SmartDashboard}. The default value is 0.2 seconds.
+ * @return the period (in seconds)
+ */
+double SendableGyro::GetUpdatePeriod()
+{
+ return m_period;
+}
+
+/**
+ * Reset the gyro.
+ * Resets the gyro to the given heading. This can be used if there is significant
+ * drift in the gyro and it needs to be recalibrated after it has been running.
+ * @param angle the angle the gyro should believe it is pointing
+ */
+void SendableGyro::ResetToAngle(double angle)
+{
+ m_offset = angle;
+ Gyro::Reset();
+}
+
+NetworkTable *SendableGyro::GetTable()
+{
+ if (m_table == NULL)
+ {
+ m_table = new NetworkTable();
+ m_table->PutInt(kAngle, (int)GetAngle());
+ m_table->AddChangeListener(kAngle, this);
+ m_publisher.Start((UINT32)this);
+ }
+ return m_table;
+}
+
+void SendableGyro::ValueChanged(NetworkTable *table, const char *name, NetworkTables_Types type)
+{
+ // Update value from smart dashboard
+ ResetToAngle(m_table->GetDouble(name));
+}
+
+void SendableGyro::PublishTaskRun()
+{
+ m_runPublisher = true;
+ while(m_runPublisher)
+ {
+ m_table->PutInt(kAngle, (int)GetAngle());
+ taskDelay((INT32)(m_period * 1000));
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/SmartDashboard/SendableGyro.h b/aos/externals/WPILib/WPILib/SmartDashboard/SendableGyro.h
new file mode 100644
index 0000000..4616b7d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SmartDashboard/SendableGyro.h
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SENDABLE_GYRO_H__
+#define __SENDABLE_GYRO_H__
+
+#include "Gyro.h"
+#include "NetworkTables/NetworkTableChangeListener.h"
+#include "SmartDashboard/SmartDashboardData.h"
+#include "Task.h"
+
+class NetworkTable;
+
+/**
+ * The {@link SendableGyro} class behaves exactly the same as a {@link Gyro} except that it
+ * also implements {@link SmartDashboardData} so that it can be sent over to the {@link SmartDashboard}.
+ */
+class SendableGyro : public Gyro, public SmartDashboardData, public NetworkTableChangeListener
+{
+public:
+ SendableGyro(UINT8 moduleNumber, UINT32 channel);
+ SendableGyro(UINT32 channel);
+ SendableGyro(AnalogChannel* channel);
+ virtual ~SendableGyro();
+
+ // Gyro overrides
+ virtual float GetAngle();
+ virtual void Reset();
+
+ void SetUpdatePeriod(double period);
+ double GetUpdatePeriod();
+ void ResetToAngle(double angle);
+
+ // SmartDashboardData interface
+ virtual std::string GetType() {return "Gyro";}
+ virtual NetworkTable *GetTable();
+
+private:
+ // NetworkTableChangeListener interface
+ virtual void ValueChanged(NetworkTable *table, const char *name, NetworkTables_Types type);
+ virtual void ValueConfirmed(NetworkTable *table, const char *name, NetworkTables_Types type) {}
+
+ void PublishTaskRun();
+
+ static int InitPublishTask(SendableGyro *obj) {obj->PublishTaskRun();return 0;}
+
+ /** The angle added to the gyro's value */
+ double m_offset;
+ /** The period (in seconds) between value updates */
+ double m_period;
+ NetworkTable *m_table;
+ Task m_publisher;
+ bool m_runPublisher;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/SmartDashboard/SendablePIDController.cpp b/aos/externals/WPILib/WPILib/SmartDashboard/SendablePIDController.cpp
new file mode 100644
index 0000000..2606a2f
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SmartDashboard/SendablePIDController.cpp
@@ -0,0 +1,145 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "SmartDashboard/SendablePIDController.h"
+
+#include "NetworkTables/NetworkTable.h"
+
+static const char *kP = "p";
+static const char *kI = "i";
+static const char *kD = "d";
+static const char *kSetpoint = "setpoint";
+static const char *kEnabled = "enabled";
+
+/**
+ * Allocate a PID object with the given constants for P, I, D, using a 50ms period.
+ * @param p the proportional coefficient
+ * @param i the integral coefficient
+ * @param d the derivative coefficient
+ * @param source The PIDSource object that is used to get values
+ * @param output The PIDOutput object that is set to the output value
+ */
+SendablePIDController::SendablePIDController(double p, double i, double d,
+ PIDSource* source, PIDOutput* output) :
+ PIDController(p, i, d, source, output),
+ m_table(NULL)
+{
+}
+
+/**
+ * Allocate a PID object with the given constants for P, I, D
+ * @param p the proportional coefficient
+ * @param i the integral coefficient
+ * @param d the derivative coefficient
+ * @param source The PIDSource object that is used to get values
+ * @param output The PIDOutput object that is set to the output value
+ * @param period the loop time for doing calculations in seconds. This particularly effects calculations of the
+ * integral and differential terms. The default is 50ms.
+ */
+SendablePIDController::SendablePIDController(double p, double i, double d,
+ PIDSource* source, PIDOutput* output, double period) :
+ PIDController(p, i, d, source, output, period),
+ m_table(NULL)
+{
+}
+
+SendablePIDController::~SendablePIDController()
+{
+ if (m_table != NULL)
+ m_table->RemoveChangeListenerAny(this);
+}
+
+/**
+ * Set the setpoint for the PIDController
+ * @param setpoint the desired setpoint
+ */
+void SendablePIDController::SetSetpoint(float setpoint)
+{
+ PIDController::SetSetpoint(setpoint);
+
+ if (m_table != NULL)
+ {
+ m_table->PutDouble(kSetpoint, setpoint);
+ }
+}
+
+/**
+ * Set the PID Controller gain parameters.
+ * Set the proportional, integral, and differential coefficients.
+ * @param p Proportional coefficient
+ * @param i Integral coefficient
+ * @param d Differential coefficient
+ */
+void SendablePIDController::SetPID(double p, double i, double d)
+{
+ PIDController::SetPID(p, i, d);
+
+ if (m_table != NULL)
+ {
+ m_table->PutDouble(kP, p);
+ m_table->PutDouble(kI, i);
+ m_table->PutDouble(kD, d);
+ }
+}
+
+/**
+ * Begin running the PIDController
+ */
+void SendablePIDController::Enable()
+{
+ PIDController::Enable();
+
+ if (m_table != NULL)
+ m_table->PutBoolean(kEnabled, true);
+}
+
+/**
+ * Stop running the PIDController, this sets the output to zero before stopping.
+ */
+void SendablePIDController::Disable()
+{
+ PIDController::Disable();
+
+ if (m_table != NULL)
+ m_table->PutBoolean(kEnabled, false);
+}
+
+NetworkTable* SendablePIDController::GetTable()
+{
+ if (m_table == NULL)
+ {
+ m_table = new NetworkTable();
+
+ m_table->PutDouble(kP, GetP());
+ m_table->PutDouble(kI, GetI());
+ m_table->PutDouble(kD, GetD());
+ m_table->PutDouble(kSetpoint, GetSetpoint());
+ m_table->PutBoolean(kEnabled, IsEnabled());
+
+ m_table->AddChangeListenerAny(this);
+ }
+ return m_table;
+}
+
+void SendablePIDController::ValueChanged(NetworkTable *table, const char *name, NetworkTables_Types type)
+{
+ if (strcmp(name, kP) == 0 || strcmp(name, kI) == 0 || strcmp(name, kD) == 0)
+ {
+ PIDController::SetPID(table->GetDouble(kP), table->GetDouble(kI),
+ table->GetDouble(kD));
+ }
+ else if (strcmp(name, kSetpoint) == 0)
+ {
+ PIDController::SetSetpoint(table->GetDouble(kSetpoint));
+ }
+ else if (strcmp(name, kEnabled) == 0)
+ {
+ if (table->GetBoolean(kEnabled))
+ PIDController::Enable();
+ else
+ PIDController::Disable();
+ }
+}
diff --git a/aos/externals/WPILib/WPILib/SmartDashboard/SendablePIDController.h b/aos/externals/WPILib/WPILib/SmartDashboard/SendablePIDController.h
new file mode 100644
index 0000000..02d6daa
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SmartDashboard/SendablePIDController.h
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SENDABLE_PID_CONTROLLER_H__
+#define __SENDABLE_PID_CONTROLLER_H__
+
+#include "NetworkTables/NetworkTableChangeListener.h"
+#include "PIDController.h"
+#include "SmartDashboard/SmartDashboardData.h"
+
+class NetworkTable;
+
+/**
+ * A {@link SendablePIDController} is a {@link PIDController} that can be sent over to the {@link SmartDashboard} using
+ * the {@link SmartDashboard#PutData(const char *, SmartDashboardData *) PutData(...)}
+ * method.
+ *
+ * <p>It is useful if you want to test values of a {@link PIDController} without having to recompile code between tests.
+ * Also, consider using {@link Preferences} to save the important values between matches.</p>
+ *
+ * @see SmartDashboard
+ */
+class SendablePIDController : public PIDController, public SmartDashboardData, public NetworkTableChangeListener
+{
+public:
+ SendablePIDController(double p, double i, double d, PIDSource *source, PIDOutput *output);
+ SendablePIDController(double p, double i, double d, PIDSource *source, PIDOutput *output, double period);
+ virtual ~SendablePIDController();
+
+ virtual void SetSetpoint(float setpoint);
+ virtual void SetPID(double p, double i, double d);
+ virtual void Enable();
+ virtual void Disable();
+
+ // SmartDashboardData interface
+ virtual std::string GetType() {return "PIDController";}
+ virtual NetworkTable *GetTable();
+
+ // NetworkTableChangeListener interface
+ virtual void ValueChanged(NetworkTable *table, const char *name, NetworkTables_Types type);
+ virtual void ValueConfirmed(NetworkTable *table, const char *name, NetworkTables_Types type) {}
+
+private:
+ NetworkTable* m_table;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboard.cpp b/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboard.cpp
new file mode 100644
index 0000000..f7c4867
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboard.cpp
@@ -0,0 +1,335 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "SmartDashboard/SmartDashboard.h"
+
+#include "NetworkCommunication/UsageReporting.h"
+#include "NetworkTables/NetworkTable.h"
+#include "SmartDashboard/SmartDashboardData.h"
+#include "SmartDashboard/SmartDashboardNamedData.h"
+#include "WPIErrors.h"
+
+SmartDashboard *SmartDashboard::_instance = NULL;
+
+/**
+ * The {@link SmartDashboard} class is the bridge between robot programs and the SmartDashboard on the
+ * laptop.
+ *
+ * <p>When a value is put into the SmartDashboard here, it pops up on the SmartDashboard on the laptop.
+ * Users can put values into and get values from the SmartDashboard</p>
+ */
+SmartDashboard::SmartDashboard()
+{
+ AddToSingletonList();
+ m_table = NetworkTable::GetTable("SmartDashboard");
+
+ nUsageReporting::report(nUsageReporting::kResourceType_SmartDashboard, nUsageReporting::kSmartDashboard_Instance);
+}
+
+SmartDashboard::~SmartDashboard()
+{
+}
+
+/**
+ * Get the one and only {@link SmartDashboard} object
+ * @return pointer to the {@link SmartDashboard}
+ */
+SmartDashboard *SmartDashboard::GetInstance()
+{
+ if (_instance == NULL)
+ {
+ _instance = new SmartDashboard();
+ }
+ return _instance;
+}
+
+
+/**
+ * Maps the specified key to the specified value in this table.
+ * The key can not be NULL.
+ * The value can be retrieved by calling the get method with a key that is equal to the original key.
+ * @param keyName the key
+ * @param value the value
+ */
+void SmartDashboard::PutData(const char *keyName, SmartDashboardData *value)
+{
+ if (keyName == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "keyName");
+ return;
+ }
+ if (value == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "value");
+ return;
+ }
+ NetworkTable *type = new NetworkTable();
+ type->PutString("~TYPE~", value->GetType());
+ type->PutSubTable("Data", value->GetTable());
+ m_table->PutSubTable(keyName, type);
+ m_tablesToData[type] = value;
+}
+
+/**
+ * Maps the specified key (where the key is the name of the {@link SmartDashboardNamedData}
+ * to the specified value in this table.
+ * The value can be retrieved by calling the get method with a key that is equal to the original key.
+ * @param value the value
+ */
+void SmartDashboard::PutData(SmartDashboardNamedData *value)
+{
+ if (value == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "value");
+ return;
+ }
+ PutData(value->GetName().c_str(), value);
+}
+
+/**
+ * Returns the value at the specified key.
+ * @param keyName the key
+ * @return the value
+ */
+SmartDashboardData *SmartDashboard::GetData(const char *keyName)
+{
+ if (keyName == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "keyName");
+ return NULL;
+ }
+ NetworkTable *subtable = m_table->GetSubTable(keyName);
+ SmartDashboardData *data = m_tablesToData[subtable];
+ if (data == NULL)
+ {
+ wpi_setWPIErrorWithContext(SmartDashboardMissingKey, keyName);
+ return NULL;
+ }
+ return data;
+}
+
+/**
+ * Maps the specified key to the specified value in this table.
+ * The key can not be NULL.
+ * The value can be retrieved by calling the get method with a key that is equal to the original key.
+ * @param keyName the key
+ * @param value the value
+ */
+void SmartDashboard::PutBoolean(const char *keyName, bool value)
+{
+ m_table->PutBoolean(keyName, value);
+}
+
+/**
+ * Returns the value at the specified key.
+ * @param keyName the key
+ * @return the value
+ */
+bool SmartDashboard::GetBoolean(const char *keyName)
+{
+ return m_table->GetBoolean(keyName);
+}
+
+/**
+* Maps the specified key to the specified value in this table.
+* The keyName can not be NULL.
+* The value can be retrieved by calling the get method with a key that is equal to the original key.
+* @param keyName the key
+* @param value the value
+*/
+void SmartDashboard::PutInt(const char *keyName, int value)
+{
+ m_table->PutInt(keyName, value);
+}
+
+/**
+ * Returns the value at the specified key.
+ * @param keyName the key
+ * @return the value
+ */
+int SmartDashboard::GetInt(const char *keyName)
+{
+ return m_table->GetInt(keyName);
+}
+
+/**
+ * Maps the specified key to the specified value in this table.
+ * The key can not be NULL.
+ * The value can be retrieved by calling the get method with a key that is equal to the original key.
+ * @param keyName the key
+ * @param value the value
+ */
+void SmartDashboard::PutDouble(const char *keyName, double value)
+{
+ m_table->PutDouble(keyName, value);
+}
+
+/**
+ * Returns the value at the specified key.
+ * @param keyName the key
+ * @return the value
+ */
+double SmartDashboard::GetDouble(const char *keyName)
+{
+ return m_table->GetDouble(keyName);
+}
+
+/**
+ * Maps the specified key to the specified value in this table.
+ * Neither the key nor the value can be NULL.
+ * The value can be retrieved by calling the get method with a key that is equal to the original key.
+ * @param keyName the key
+ * @param value the value
+ */
+void SmartDashboard::PutString(const char *keyName, const char *value)
+{
+ m_table->PutString(keyName, value);
+}
+
+/**
+ * Returns the value at the specified key.
+ * @param keyName the key
+ * @param value the buffer to fill with the value
+ * @param valueLen the size of the buffer pointed to by value
+ * @return the length of the string
+ */
+int SmartDashboard::GetString(const char *keyName, char *value, int valueLen)
+{
+ return m_table->GetString(keyName, value, valueLen);
+}
+
+/**
+ * Maps the specified key to the specified value in this table.
+ * Neither the key nor the value can be NULL.
+ * The value can be retrieved by calling the get method with a key that is equal to the original key.
+ * @param keyName the key
+ * @param value the value
+ */
+void SmartDashboard::PutString(std::string keyName, std::string value)
+{
+ m_table->PutString(keyName, value);
+}
+
+/**
+ * Returns the value at the specified key.
+ * @param keyName the key
+ * @return the value
+ */
+std::string SmartDashboard::GetString(std::string keyName)
+{
+ return m_table->GetString(keyName);
+}
+
+/**
+ * @deprecated no longer necessary
+ */
+void SmartDashboard::init()
+{
+}
+
+/**
+ * Send the given byte value to the client as the field with the given name.
+ * @param value The value to be displayed on the client.
+ * @param name The name of the field.
+ * @return An integer status code.
+ * @deprecated use {@link SmartDashboard#PutInt(const char*, int)}
+ */
+int SmartDashboard::LogChar(char value, const char *name)
+{
+ GetInstance()->PutInt(name, value);
+ return 0;
+}
+
+/**
+ * Send the given UTF-16 char value to the client as the field with the given name.
+ * @param value The value to be displayed on the client.
+ * @param name The name of the field.
+ * @return An integer status code.
+ * @deprecated use {@link SmartDashboard#PutInt(const char*, int)}
+ */
+int SmartDashboard::LogChar(wchar_t value, const char *name)
+{
+ GetInstance()->PutInt(name, value);
+ return 0;
+}
+
+/**
+ * Sends the given int value to the client as the field with the given name.
+ * @param value The value to send.
+ * @param name The name of the field.
+ * @return An integer status code.
+ * @deprecated use {@link SmartDashboard#PutInt(const char*, int)}
+ */
+int SmartDashboard::Log(INT32 value, const char *name)
+{
+ GetInstance()->PutInt(name, value);
+ return 0;
+}
+
+/**
+ * Sends the given long value to the client as the field with the given name.
+ * @param value The value to send.
+ * @param name The name of the field.
+ * @return An integer status code.
+ * @deprecated use {@link SmartDashboard#PutDouble(const char*, double)}
+ */
+int SmartDashboard::Log(INT64 value, const char *name)
+{
+ GetInstance()->PutDouble(name, value);
+ return 0;
+}
+
+/**
+ * Sends the given boolean value to the client as the field with the given name.
+ * @param value The value to send.
+ * @param name The name of the field.
+ * @return An integer status code.
+ * @deprecated use {@link SmartDashboard#PutBoolean(const char*, bool)} instead
+ */
+int SmartDashboard::Log(bool value, const char *name)
+{
+ GetInstance()->PutBoolean(name, value);
+ return 0;
+}
+
+/**
+ * Sends the given float value to the client as the field with the given name.
+ * @param value The value to send.
+ * @param name The name of the field.
+ * @return An integer status code.
+ * @deprecated use {@link SmartDashboard#PutDouble(const char*, double)}
+ */
+int SmartDashboard::Log(float value, const char *name)
+{
+ GetInstance()->PutDouble(name, value);
+ return 0;
+}
+
+/**
+ * Sends the given double value to the client as the field with the given name.
+ * @param value The value to send.
+ * @param name The name of the field.
+ * @return An integer status code.
+ * @deprecated use {@link SmartDashboard#PutDouble(const char*, double)}
+ */
+int SmartDashboard::Log(double value, const char *name)
+{
+ GetInstance()->PutDouble(name, value);
+ return 0;
+}
+
+/**
+ * Sends the given string value to the client as the field with the given name.
+ * @param value The value to send. This may be at most 63 characters in length.
+ * @param name The name of the field.
+ * @return An integer status code.
+ * @deprecated use {@link SmartDashboard#PutString(const char*, const char*)}
+ */
+int SmartDashboard::Log(const char* value, const char *name)
+{
+ GetInstance()->PutString(name, value);
+ return 0;
+}
diff --git a/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboard.h b/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboard.h
new file mode 100644
index 0000000..38f1f95
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboard.h
@@ -0,0 +1,64 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SMART_DASHBOARD_H__
+#define __SMART_DASHBOARD_H__
+
+#include "SensorBase.h"
+#include <map>
+#include <string>
+
+class NetworkTable;
+class SmartDashboardData;
+class SmartDashboardNamedData;
+
+class SmartDashboard : public SensorBase
+{
+public:
+ static SmartDashboard *GetInstance();
+
+ void PutData(const char *keyName, SmartDashboardData *value);
+ void PutData(SmartDashboardNamedData *value);
+ SmartDashboardData* GetData(const char *keyName);
+ void PutBoolean(const char *keyName, bool value);
+ bool GetBoolean(const char *keyName);
+ void PutInt(const char *keyName, int value);
+ int GetInt(const char *keyName);
+ void PutDouble(const char *keyName, double value);
+ double GetDouble(const char *keyName);
+ void PutString(const char *keyName, const char *value);
+ int GetString(const char *keyName, char *value, int valueLen);
+ std::string GetString(std::string keyName);
+ void PutString(std::string keyName, std::string value);
+
+ void init();
+ static int LogChar(char value, const char *name);
+ static int LogChar(wchar_t value, const char *name);
+ static int Log(INT32 value, const char *name);
+ static int Log(INT64 value, const char *name);
+ static int Log(bool value, const char *name);
+ static int Log(float value, const char *name);
+ static int Log(double value, const char *name);
+ static int Log(const char *value, const char *name);
+
+private:
+ SmartDashboard();
+ virtual ~SmartDashboard();
+ DISALLOW_COPY_AND_ASSIGN(SmartDashboard);
+
+ static SmartDashboard *_instance;
+
+ /** The {@link NetworkTable} used by {@link SmartDashboard} */
+ NetworkTable *m_table;
+ /**
+ * A map linking tables in the SmartDashboard to the {@link SmartDashboardData} objects
+ * they came from.
+ */
+ std::map<NetworkTable *, SmartDashboardData *> m_tablesToData;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboardData.h b/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboardData.h
new file mode 100644
index 0000000..4fe43a7
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboardData.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SMART_DASHBOARD_DATA__
+#define __SMART_DASHBOARD_DATA__
+
+#include <string>
+
+class NetworkTable;
+
+class SmartDashboardData
+{
+public:
+ virtual std::string GetType() = 0;
+ virtual NetworkTable *GetTable() = 0;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboardNamedData.h b/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboardNamedData.h
new file mode 100644
index 0000000..c0c1531
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SmartDashboard/SmartDashboardNamedData.h
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __SMART_DASHBOARD_NAMED_DATA__
+#define __SMART_DASHBOARD_NAMED_DATA__
+
+#include "SmartDashboard/SmartDashboardData.h"
+
+class SmartDashboardNamedData : public SmartDashboardData
+{
+public:
+ virtual std::string GetName() = 0;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Solenoid.cpp b/aos/externals/WPILib/WPILib/Solenoid.cpp
new file mode 100644
index 0000000..4c7307c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Solenoid.cpp
@@ -0,0 +1,101 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Solenoid.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+
+/**
+ * Common function to implement constructor behavior.
+ */
+void Solenoid::InitSolenoid()
+{
+ char buf[64];
+ if (!CheckSolenoidModule(m_moduleNumber))
+ {
+ snprintf(buf, 64, "Solenoid Module %d", m_moduleNumber);
+ wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf);
+ return;
+ }
+ if (!CheckSolenoidChannel(m_channel))
+ {
+ snprintf(buf, 64, "Solenoid Channel %d", m_channel);
+ wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+ return;
+ }
+ Resource::CreateResourceObject(&m_allocated, tSolenoid::kNumDO7_0Elements * kSolenoidChannels);
+
+ snprintf(buf, 64, "Solenoid %d (Module: %d)", m_channel, m_moduleNumber);
+ if (m_allocated->Allocate((m_moduleNumber - 1) * kSolenoidChannels + m_channel - 1, buf) == ~0ul)
+ {
+ CloneError(m_allocated);
+ return;
+ }
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Solenoid, m_channel, m_moduleNumber - 1);
+}
+
+/**
+ * Constructor.
+ *
+ * @param channel The channel on the solenoid module to control (1..8).
+ */
+Solenoid::Solenoid(UINT32 channel)
+ : SolenoidBase (GetDefaultSolenoidModule())
+ , m_channel (channel)
+{
+ InitSolenoid();
+}
+
+/**
+ * Constructor.
+ *
+ * @param moduleNumber The solenoid module (1 or 2).
+ * @param channel The channel on the solenoid module to control (1..8).
+ */
+Solenoid::Solenoid(UINT8 moduleNumber, UINT32 channel)
+ : SolenoidBase (moduleNumber)
+ , m_channel (channel)
+{
+ InitSolenoid();
+}
+
+/**
+ * Destructor.
+ */
+Solenoid::~Solenoid()
+{
+ if (CheckSolenoidModule(m_moduleNumber))
+ {
+ m_allocated->Free((m_moduleNumber - 1) * kSolenoidChannels + m_channel - 1);
+ }
+}
+
+/**
+ * Set the value of a solenoid.
+ *
+ * @param on Turn the solenoid output off or on.
+ */
+void Solenoid::Set(bool on)
+{
+ if (StatusIsFatal()) return;
+ UINT8 value = on ? 0xFF : 0x00;
+ UINT8 mask = 1 << (m_channel - 1);
+
+ SolenoidBase::Set(value, mask);
+}
+
+/**
+ * Read the current value of the solenoid.
+ *
+ * @return The current value of the solenoid.
+ */
+bool Solenoid::Get()
+{
+ if (StatusIsFatal()) return false;
+ UINT8 value = GetAll() & ( 1 << (m_channel - 1));
+ return (value != 0);
+}
diff --git a/aos/externals/WPILib/WPILib/Solenoid.h b/aos/externals/WPILib/WPILib/Solenoid.h
new file mode 100644
index 0000000..b0ea4fd
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Solenoid.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef SOLENOID_H_
+#define SOLENOID_H_
+
+#include "SolenoidBase.h"
+
+/**
+ * Solenoid class for running high voltage Digital Output (9472 module).
+ *
+ * The Solenoid class is typically used for pneumatics solenoids, but could be used
+ * for any device within the current spec of the 9472 module.
+ */
+class Solenoid : public SolenoidBase {
+public:
+ explicit Solenoid(UINT32 channel);
+ Solenoid(UINT8 moduleNumber, UINT32 channel);
+ virtual ~Solenoid();
+ virtual void Set(bool on);
+ virtual bool Get();
+
+private:
+ void InitSolenoid();
+
+ UINT32 m_channel; ///< The channel on the module to control.
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/SolenoidBase.cpp b/aos/externals/WPILib/WPILib/SolenoidBase.cpp
new file mode 100644
index 0000000..4be4e18
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SolenoidBase.cpp
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "SolenoidBase.h"
+
+// Needs to be global since the protected resource spans all Solenoid objects.
+Semaphore SolenoidBase::m_semaphore;
+Resource *SolenoidBase::m_allocated = NULL;
+
+tSolenoid *SolenoidBase::m_fpgaSolenoidModule = NULL;
+UINT32 SolenoidBase::m_refCount = 0;
+
+
+/**
+ * Constructor
+ *
+ * @param moduleNumber The solenoid module (1 or 2).
+ */
+SolenoidBase::SolenoidBase(UINT8 moduleNumber)
+ : m_moduleNumber (moduleNumber)
+{
+ Synchronized sync(m_semaphore);
+ m_refCount++;
+ if (m_refCount == 1)
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_fpgaSolenoidModule = tSolenoid::create(&localStatus);
+ wpi_setError(localStatus);
+ }
+}
+
+/**
+ * Destructor.
+ */
+SolenoidBase::~SolenoidBase()
+{
+ Synchronized sync(m_semaphore);
+ if (CheckSolenoidModule(m_moduleNumber))
+ {
+ if (m_refCount == 1)
+ {
+ delete m_fpgaSolenoidModule;
+ m_fpgaSolenoidModule = NULL;
+ }
+ m_refCount--;
+ }
+}
+
+/**
+ * Set the value of a solenoid.
+ *
+ * @param value The value you want to set on the module.
+ * @param mask The channels you want to be affected.
+ */
+void SolenoidBase::Set(UINT8 value, UINT8 mask)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ if (CheckSolenoidModule(m_moduleNumber))
+ {
+ Synchronized sync(m_semaphore);
+ UINT8 currentValue = m_fpgaSolenoidModule->readDO7_0(m_moduleNumber - 1, &localStatus);
+ // Zero out the values to change
+ currentValue = currentValue & ~mask;
+ currentValue = currentValue | (value & mask);
+ m_fpgaSolenoidModule->writeDO7_0(m_moduleNumber - 1, currentValue, &localStatus);
+ }
+ wpi_setError(localStatus);
+}
+
+/**
+ * Read all 8 solenoids as a single byte
+ *
+ * @return The current value of all 8 solenoids on the module.
+ */
+UINT8 SolenoidBase::GetAll()
+{
+ if (CheckSolenoidModule(m_moduleNumber))
+ {
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT8 solenoids = m_fpgaSolenoidModule->readDO7_0(m_moduleNumber - 1, &localStatus);
+ wpi_setError(localStatus);
+ return solenoids;
+ }
+ return 0;
+}
diff --git a/aos/externals/WPILib/WPILib/SolenoidBase.h b/aos/externals/WPILib/WPILib/SolenoidBase.h
new file mode 100644
index 0000000..ddfb958
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SolenoidBase.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef SOLENOID_BASE_H_
+#define SOLENOID_BASE_H_
+
+#include "Resource.h"
+#include "SensorBase.h"
+#include "ChipObject.h"
+#include "Synchronized.h"
+
+/**
+ * SolenoidBase class is the common base class for the Solenoid and
+ * DoubleSolenoid classes.
+ */
+class SolenoidBase : public SensorBase {
+public:
+ virtual ~SolenoidBase();
+ UINT8 GetAll();
+
+protected:
+ explicit SolenoidBase(UINT8 moduleNumber);
+ void Set(UINT8 value, UINT8 mask);
+ virtual void InitSolenoid() = 0;
+
+ UINT32 m_moduleNumber; ///< Slot number where the module is plugged into the chassis.
+ static Resource *m_allocated;
+
+private:
+ static tSolenoid *m_fpgaSolenoidModule; ///< FPGA Solenoid Module object.
+ static UINT32 m_refCount; ///< Reference count for the chip object.
+ static Semaphore m_semaphore;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/SpeedController.h b/aos/externals/WPILib/WPILib/SpeedController.h
new file mode 100644
index 0000000..c5bba38
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/SpeedController.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef SPEED_CONTROLLER_H
+#define SPEED_CONTROLLER_H
+
+#include <vxWorks.h>
+
+/**
+ * Interface for speed controlling devices.
+ */
+class SpeedController
+{
+public:
+ virtual ~SpeedController() {};
+ /**
+ * Common interface for setting the speed of a speed controller.
+ *
+ * @param speed The speed to set. Value should be between -1.0 and 1.0.
+ * @param syncGroup The update group to add this Set() to, pending UpdateSyncGroup(). If 0, update immediately.
+ */
+ virtual void Set(float speed, UINT8 syncGroup=0) = 0;
+ /**
+ * Common interface for getting the current set speed of a speed controller.
+ *
+ * @return The current set speed. Value is between -1.0 and 1.0.
+ */
+ virtual float Get() = 0;
+ /**
+ * Common interface for disabling a motor.
+ */
+ virtual void Disable() = 0;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Synchronized.cpp b/aos/externals/WPILib/WPILib/Synchronized.cpp
new file mode 100644
index 0000000..962caf0
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Synchronized.cpp
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Synchronized.h"
+
+/**
+ * Semaphore class deals with low-level vxworks semaphores.
+ * The Semaphore class is very useful for static variables because it takes care of creating and
+ * deleting the raw vxworks system semaphore at load and unload time.
+ * This constructor will create the semaphore with semBCreate(SEM_Q_PRIORITY, SEM_FULL).
+ */
+Semaphore::Semaphore()
+{
+ m_semaphore = semBCreate(SEM_Q_PRIORITY, SEM_FULL);
+}
+/**
+ * Semaphore destructor.
+ * This destructor deletes the semaphore ensuring that the code does not leak vxworks system resources.
+ */
+Semaphore::~Semaphore()
+{
+ semDelete(m_semaphore);
+}
+/**
+ * Retrieve the raw vxworks semaphore.
+ */
+SEM_ID Semaphore::get()
+{
+ return m_semaphore;
+}
+
+/**
+ * Take the semaphore.
+ *
+ * Taking the semaphore is also called locking. If the semaphore is not
+ * currently taken, it will block until it is given.
+ *
+ * @return 0 for success and -1 for error. If -1, the error will be in errno.
+ */
+int Semaphore::Take()
+{
+ return semTake(m_semaphore, WAIT_FOREVER);
+}
+/**
+ * Give the semaphore.
+ *
+ * Giving the semaphore is also called unlocking. If another task is currently
+ * waiting to take the semaphore, it will succeed.
+ *
+ * @return 0 for success and -1 for error. If -1, the error will be in errno.
+ */
+int Semaphore::Give()
+{
+ return semGive(m_semaphore);
+}
+
+/**
+ * Synchronized class deals with critical regions.
+ * Declare a Synchronized object at the beginning of a block. That will take the semaphore.
+ * When the code exits from the block it will call the destructor which will give the semaphore.
+ * This ensures that no matter how the block is exited, the semaphore will always be released.
+ * Use the CRITICAL_REGION(SEM_ID) and END_REGION macros to make the code look cleaner (see header file)
+ * @param semaphore The semaphore controlling this critical region.
+ */
+Synchronized::Synchronized(SEM_ID semaphore)
+{
+ m_semaphore = semaphore;
+ semTake(m_semaphore, WAIT_FOREVER);
+}
+Synchronized::Synchronized(Semaphore &semaphore)
+{
+ m_semaphore = semaphore.get();
+ semTake(m_semaphore, WAIT_FOREVER);
+}
+
+/**
+ * Synchronized destructor.
+ * This destructor frees the semaphore ensuring that the resource is freed for the block
+ * containing the Synchronized object.
+ */
+Synchronized::~Synchronized()
+{
+ semGive(m_semaphore);
+}
diff --git a/aos/externals/WPILib/WPILib/Synchronized.h b/aos/externals/WPILib/WPILib/Synchronized.h
new file mode 100644
index 0000000..f70557c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Synchronized.h
@@ -0,0 +1,64 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef SYNCHRONIZED_H
+#define SYNCHRONIZED_H
+
+#include <semLib.h>
+
+#include "Base.h"
+
+#define CRITICAL_REGION(s) { Synchronized _sync(s);
+#define END_REGION }
+
+class Synchronized;
+
+/**
+ * Wrap a raw vxworks semaphore (SEM_ID).
+ * This class wraps a raw vxworks semaphore so that it is created and destroyed
+ * with C++ constructors and destructors.
+ * This class is safe to use in static variables because it does not depend on
+ * any other C++ static constructors or destructors.
+ */
+class Semaphore
+{
+public:
+ Semaphore();
+ ~Semaphore();
+ int Take();
+ int Give();
+private:
+ SEM_ID m_semaphore;
+ SEM_ID get();
+
+ // TODO somebody should change Synchronized to not support raw SEM_IDs and
+ // instead use Take() and Give() directly so this can go away
+ friend class Synchronized;
+ DISALLOW_COPY_AND_ASSIGN(Semaphore);
+};
+
+/**
+ * Provide easy support for critical regions.
+ * A critical region is an area of code that is always executed under mutual exclusion. Only
+ * one task can be executing this code at any time. The idea is that code that manipulates data
+ * that is shared between two or more tasks has to be prevented from executing at the same time
+ * otherwise a race condition is possible when both tasks try to update the data. Typically
+ * semaphores are used to ensure only single task access to the data.
+ * Synchronized objects are a simple wrapper around semaphores to help ensure that semaphores
+ * are always signaled (semGive) after a wait (semTake).
+ */
+class Synchronized
+{
+public:
+ explicit Synchronized(SEM_ID);
+ explicit Synchronized(Semaphore&);
+ virtual ~Synchronized();
+private:
+ SEM_ID m_semaphore;
+ DISALLOW_COPY_AND_ASSIGN(Synchronized);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Task.cpp b/aos/externals/WPILib/WPILib/Task.cpp
new file mode 100644
index 0000000..4568246
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Task.cpp
@@ -0,0 +1,216 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Task.h"
+
+#include "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+#include <errnoLib.h>
+#include <string.h>
+#include <taskLib.h>
+#include <usrLib.h>
+
+const UINT32 Task::kDefaultPriority;
+const INT32 Task::kInvalidTaskID;
+
+/**
+ * Create but don't launch a task.
+ * @param name The name of the task. "FRC_" will be prepended to the task name.
+ * @param function The address of the function to run as the new task.
+ * @param priority The VxWorks priority for the task.
+ * @param stackSize The size of the stack for the task
+ */
+Task::Task(const char* name, FUNCPTR function, INT32 priority, UINT32 stackSize)
+{
+ m_taskID = kInvalidTaskID;
+ m_function = function;
+ m_priority = priority;
+ m_stackSize = stackSize;
+ m_taskName = new char[strlen(name) + 5];
+ strcpy(m_taskName, "FRC_");
+ strcpy(m_taskName+4, name);
+
+ static INT32 instances = 0;
+ instances++;
+ nUsageReporting::report(nUsageReporting::kResourceType_Task, instances, 0, m_taskName);
+}
+
+Task::~Task()
+{
+ if (m_taskID != kInvalidTaskID) Stop();
+ delete [] m_taskName;
+ m_taskName = NULL;
+}
+
+/**
+ * Starts this task.
+ * If it is already running or unable to start, it fails and returns false.
+ */
+bool Task::Start(UINT32 arg0, UINT32 arg1, UINT32 arg2, UINT32 arg3, UINT32 arg4,
+ UINT32 arg5, UINT32 arg6, UINT32 arg7, UINT32 arg8, UINT32 arg9)
+{
+ m_taskID = taskSpawn(m_taskName,
+ m_priority,
+ VX_FP_TASK, // options
+ m_stackSize, // stack size
+ m_function, // function to start
+ arg0, arg1, arg2, arg3, arg4, // parameter 1 - pointer to this class
+ arg5, arg6, arg7, arg8, arg9);// additional unused parameters
+ bool ok = HandleError(m_taskID);
+ if (!ok) m_taskID = kInvalidTaskID;
+ return ok;
+}
+
+/**
+ * Restarts a running task.
+ * If the task isn't started, it starts it.
+ * @return false if the task is running and we are unable to kill the previous instance
+ */
+bool Task::Restart()
+{
+ return HandleError(taskRestart(m_taskID));
+}
+
+/**
+ * Kills the running task.
+ * @returns true on success false if the task doesn't exist or we are unable to kill it.
+ */
+bool Task::Stop()
+{
+ bool ok = true;
+ if (Verify())
+ {
+ ok = HandleError(taskDelete(m_taskID));
+ }
+ m_taskID = kInvalidTaskID;
+ return ok;
+}
+
+/**
+ * Returns true if the task is ready to execute (i.e. not suspended, delayed, or blocked).
+ * @return true if ready, false if not ready.
+ */
+bool Task::IsReady()
+{
+ return taskIsReady(m_taskID);
+}
+
+/**
+ * Returns true if the task was explicitly suspended by calling Suspend()
+ * @return true if suspended, false if not suspended.
+ */
+bool Task::IsSuspended()
+{
+ return taskIsSuspended(m_taskID);
+}
+
+/**
+ * Pauses a running task.
+ * Returns true on success, false if unable to pause or the task isn't running.
+ */
+bool Task::Suspend()
+{
+ return HandleError(taskSuspend(m_taskID));
+}
+
+/**
+ * Resumes a paused task.
+ * Returns true on success, false if unable to resume or if the task isn't running/paused.
+ */
+bool Task::Resume()
+{
+ return HandleError(taskResume(m_taskID));
+}
+
+/**
+ * Verifies a task still exists.
+ * @returns true on success.
+ */
+bool Task::Verify()
+{
+ return taskIdVerify(m_taskID) == OK;
+}
+
+/**
+ * Gets the priority of a task.
+ * @returns task priority or 0 if an error occured
+ */
+INT32 Task::GetPriority()
+{
+ if (HandleError(taskPriorityGet(m_taskID, &m_priority)))
+ return m_priority;
+ else
+ return 0;
+}
+
+/**
+ * This routine changes a task's priority to a specified priority.
+ * Priorities range from 0, the highest priority, to 255, the lowest priority.
+ * Default task priority is 100.
+ * @param priority The priority the task should run at.
+ * @returns true on success.
+ */
+bool Task::SetPriority(INT32 priority)
+{
+ m_priority = priority;
+ return HandleError(taskPrioritySet(m_taskID, m_priority));
+}
+
+/**
+ * Returns the name of the task.
+ * @returns Pointer to the name of the task or NULL if not allocated
+ */
+const char* Task::GetName()
+{
+ return m_taskName;
+}
+
+/**
+ * Get the ID of a task
+ * @returns Task ID of this task. Task::kInvalidTaskID (-1) if the task has not been started or has already exited.
+ */
+INT32 Task::GetID()
+{
+ if (Verify())
+ return m_taskID;
+ return kInvalidTaskID;
+}
+
+/**
+ * Handles errors generated by task related code.
+ */
+bool Task::HandleError(STATUS results)
+{
+ if (results != ERROR) return true;
+ switch(errnoGet())
+ {
+ case S_objLib_OBJ_ID_ERROR:
+ wpi_setWPIErrorWithContext(TaskIDError, m_taskName);
+ break;
+
+ case S_objLib_OBJ_DELETED:
+ wpi_setWPIErrorWithContext(TaskDeletedError, m_taskName);
+ break;
+
+ case S_taskLib_ILLEGAL_OPTIONS:
+ wpi_setWPIErrorWithContext(TaskOptionsError, m_taskName);
+ break;
+
+ case S_memLib_NOT_ENOUGH_MEMORY:
+ wpi_setWPIErrorWithContext(TaskMemoryError, m_taskName);
+ break;
+
+ case S_taskLib_ILLEGAL_PRIORITY:
+ wpi_setWPIErrorWithContext(TaskPriorityError, m_taskName);
+ break;
+
+ default:
+ printErrno(errnoGet());
+ wpi_setWPIErrorWithContext(TaskError, m_taskName);
+ }
+ return false;
+}
+
diff --git a/aos/externals/WPILib/WPILib/Task.h b/aos/externals/WPILib/WPILib/Task.h
new file mode 100644
index 0000000..03c9555
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Task.h
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __TASK_H__
+#define __TASK_H__
+
+#include "ErrorBase.h"
+#include <vxWorks.h>
+
+/**
+ * WPI task is a wrapper for the native Task object.
+ * All WPILib tasks are managed by a static task manager for simplified cleanup.
+ **/
+class Task : public ErrorBase
+{
+public:
+ static const UINT32 kDefaultPriority = 101;
+ static const INT32 kInvalidTaskID = -1;
+
+ Task(const char* name, FUNCPTR function, INT32 priority = kDefaultPriority, UINT32 stackSize = 20000);
+ virtual ~Task();
+
+ bool Start(UINT32 arg0 = 0, UINT32 arg1 = 0, UINT32 arg2 = 0, UINT32 arg3 = 0, UINT32 arg4 = 0,
+ UINT32 arg5 = 0, UINT32 arg6 = 0, UINT32 arg7 = 0, UINT32 arg8 = 0, UINT32 arg9 = 0);
+ bool Restart();
+ bool Stop();
+
+ bool IsReady();
+ bool IsSuspended();
+
+ bool Suspend();
+ bool Resume();
+
+ bool Verify();
+
+ INT32 GetPriority();
+ bool SetPriority(INT32 priority);
+ const char* GetName();
+ INT32 GetID();
+
+private:
+ FUNCPTR m_function;
+ char* m_taskName;
+ INT32 m_taskID;
+ UINT32 m_stackSize;
+ INT32 m_priority;
+ bool HandleError(STATUS results);
+ DISALLOW_COPY_AND_ASSIGN(Task);
+};
+
+#endif // __TASK_H__
diff --git a/aos/externals/WPILib/WPILib/Timer.cpp b/aos/externals/WPILib/WPILib/Timer.cpp
new file mode 100644
index 0000000..e9fcde7
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Timer.cpp
@@ -0,0 +1,203 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Timer.h"
+
+#include <sysLib.h> // for sysClkRateGet
+#include <time.h>
+#include <usrLib.h> // for taskDelay
+
+#include "Synchronized.h"
+#include "Utility.h"
+
+/**
+ * Pause the task for a specified time.
+ *
+ * Pause the execution of the program for a specified period of time given in seconds.
+ * Motors will continue to run at their last assigned values, and sensors will continue to
+ * update. Only the task containing the wait will pause until the wait time is expired.
+ *
+ * @param seconds Length of time to pause, in seconds.
+ */
+void Wait(double seconds)
+{
+ if (seconds < 0.0) return;
+ taskDelay((INT32)((double)sysClkRateGet() * seconds));
+}
+
+/*
+ * Return the FPGA system clock time in seconds.
+ * This is deprecated and just forwards to Timer::GetFPGATimestamp().
+ * @returns Robot running time in seconds.
+ */
+double GetClock()
+{
+ return Timer::GetFPGATimestamp();
+}
+
+/**
+ * @brief Gives real-time clock system time with nanosecond resolution
+ * @return The time, just in case you want the robot to start autonomous at 8pm on Saturday.
+*/
+double GetTime()
+{
+ struct timespec tp;
+
+ clock_gettime(CLOCK_REALTIME,&tp);
+ double realTime = (double)tp.tv_sec + (double)((double)tp.tv_nsec*1e-9);
+
+ return (realTime);
+}
+
+/**
+ * Create a new timer object.
+ *
+ * Create a new timer object and reset the time to zero. The timer is initially not running and
+ * must be started.
+ */
+Timer::Timer()
+ : m_startTime (0.0)
+ , m_accumulatedTime (0.0)
+ , m_running (false)
+ , m_semaphore (0)
+{
+ //Creates a semaphore to control access to critical regions.
+ //Initially 'open'
+ m_semaphore = semMCreate(SEM_Q_PRIORITY | SEM_DELETE_SAFE | SEM_INVERSION_SAFE);
+ Reset();
+}
+
+Timer::~Timer()
+{
+ semDelete(m_semaphore);
+}
+
+/**
+ * Get the current time from the timer. If the clock is running it is derived from
+ * the current system clock the start time stored in the timer class. If the clock
+ * is not running, then return the time when it was last stopped.
+ *
+ * @return unsigned Current time value for this timer in seconds
+ */
+double Timer::Get()
+{
+ double result;
+ double currentTime = GetFPGATimestamp();
+
+ Synchronized sync(m_semaphore);
+ if(m_running)
+ {
+ // This math won't work if the timer rolled over (71 minutes after boot).
+ // TODO: Check for it and compensate.
+ result = (currentTime - m_startTime) + m_accumulatedTime;
+ }
+ else
+ {
+ result = m_accumulatedTime;
+ }
+
+ return result;
+}
+
+/**
+ * Reset the timer by setting the time to 0.
+ *
+ * Make the timer startTime the current time so new requests will be relative to now
+ */
+void Timer::Reset()
+{
+ Synchronized sync(m_semaphore);
+ m_accumulatedTime = 0;
+ m_startTime = GetFPGATimestamp();
+}
+
+/**
+ * Start the timer running.
+ * Just set the running flag to true indicating that all time requests should be
+ * relative to the system clock.
+ */
+void Timer::Start()
+{
+ Synchronized sync(m_semaphore);
+ if (!m_running)
+ {
+ m_startTime = GetFPGATimestamp();
+ m_running = true;
+ }
+}
+
+/**
+ * Stop the timer.
+ * This computes the time as of now and clears the running flag, causing all
+ * subsequent time requests to be read from the accumulated time rather than
+ * looking at the system clock.
+ */
+void Timer::Stop()
+{
+ double temp = Get();
+
+ Synchronized sync(m_semaphore);
+ if (m_running)
+ {
+ m_accumulatedTime += temp;
+ m_running = false;
+ }
+}
+
+/**
+ * Check if the period specified has passed and if it has, advance the start
+ * time by that period. This is useful to decide if it's time to do periodic
+ * work without drifting later by the time it took to get around to checking.
+ *
+ * @param period The period to check for (in seconds).
+ * @return If the period has passed.
+ */
+bool Timer::HasPeriodPassed(double period)
+{
+ if (Get() > period)
+ {
+ Synchronized sync(m_semaphore);
+ // Advance the start time by the period.
+ // Don't set it to the current time... we want to avoid drift.
+ m_startTime += period;
+ return true;
+ }
+ return false;
+}
+
+/*
+ * Return the FPGA system clock time in seconds.
+ *
+ * Return the time from the FPGA hardware clock in seconds since the FPGA
+ * started.
+ * Rolls over after 71 minutes.
+ * @returns Robot running time in seconds.
+ */
+double Timer::GetFPGATimestamp()
+{
+ // FPGA returns the timestamp in microseconds
+ // Call the helper GetFPGATime() in Utility.cpp
+ return GetFPGATime() * 1.0e-6;
+}
+
+// Internal function that reads the PPC timestamp counter.
+extern "C"
+{
+ UINT32 niTimestamp32(void);
+ UINT64 niTimestamp64(void);
+}
+
+/*
+ * Return the PowerPC timestamp since boot in seconds.
+ *
+ * This is lower overhead than GetFPGATimestamp() but not synchronized with other FPGA timestamps.
+ * @returns Robot running time in seconds.
+ */
+double Timer::GetPPCTimestamp()
+{
+ // PPC system clock is 33MHz
+ return niTimestamp64() / 33.0e6;
+}
diff --git a/aos/externals/WPILib/WPILib/Timer.h b/aos/externals/WPILib/WPILib/Timer.h
new file mode 100644
index 0000000..c4cbf65
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Timer.h
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef TIMER_H_
+#define TIMER_H_
+
+#include "semLib.h"
+#include "Base.h"
+
+typedef void (*TimerInterruptHandler)(void *param);
+
+void Wait(double seconds);
+double GetClock();
+double GetTime();
+
+
+/**
+ * Timer objects measure accumulated time in seconds.
+ * The timer object functions like a stopwatch. It can be started, stopped, and cleared. When the
+ * timer is running its value counts up in seconds. When stopped, the timer holds the current
+ * value. The implementation simply records the time when started and subtracts the current time
+ * whenever the value is requested.
+ */
+class Timer
+{
+public:
+ Timer();
+ virtual ~Timer();
+ double Get();
+ void Reset();
+ void Start();
+ void Stop();
+ bool HasPeriodPassed(double period);
+
+ static double GetFPGATimestamp();
+ static double GetPPCTimestamp();
+
+private:
+ double m_startTime;
+ double m_accumulatedTime;
+ bool m_running;
+ SEM_ID m_semaphore;
+ DISALLOW_COPY_AND_ASSIGN(Timer);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Ultrasonic.cpp b/aos/externals/WPILib/WPILib/Ultrasonic.cpp
new file mode 100644
index 0000000..24cfb74
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Ultrasonic.cpp
@@ -0,0 +1,330 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Ultrasonic.h"
+
+#include "Counter.h"
+#include "DigitalInput.h"
+#include "DigitalOutput.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "Timer.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+const double Ultrasonic::kPingTime; ///< Time (sec) for the ping trigger pulse.
+const UINT32 Ultrasonic::kPriority; ///< Priority that the ultrasonic round robin task runs.
+const double Ultrasonic::kMaxUltrasonicTime; ///< Max time (ms) between readings.
+const double Ultrasonic::kSpeedOfSoundInchesPerSec;
+Task Ultrasonic::m_task("UltrasonicChecker", (FUNCPTR)UltrasonicChecker); // task doing the round-robin automatic sensing
+Ultrasonic *Ultrasonic::m_firstSensor = NULL; // head of the ultrasonic sensor list
+bool Ultrasonic::m_automaticEnabled = false; // automatic round robin mode
+SEM_ID Ultrasonic::m_semaphore = 0;
+
+/**
+ * Background task that goes through the list of ultrasonic sensors and pings each one in turn. The counter
+ * is configured to read the timing of the returned echo pulse.
+ *
+ * DANGER WILL ROBINSON, DANGER WILL ROBINSON:
+ * This code runs as a task and assumes that none of the ultrasonic sensors will change while it's
+ * running. If one does, then this will certainly break. Make sure to disable automatic mode before changing
+ * anything with the sensors!!
+ */
+void Ultrasonic::UltrasonicChecker()
+{
+ Ultrasonic *u = NULL;
+ while (m_automaticEnabled)
+ {
+ if (u == NULL) u = m_firstSensor;
+ if (u == NULL) return;
+ if (u->IsEnabled())
+ u->m_pingChannel->Pulse(kPingTime); // do the ping
+ u = u->m_nextSensor;
+ Wait(0.1); // wait for ping to return
+ }
+}
+
+/**
+ * Initialize the Ultrasonic Sensor.
+ * This is the common code that initializes the ultrasonic sensor given that there
+ * are two digital I/O channels allocated. If the system was running in automatic mode (round robin)
+ * when the new sensor is added, it is stopped, the sensor is added, then automatic mode is
+ * restored.
+ */
+void Ultrasonic::Initialize()
+{
+ bool originalMode = m_automaticEnabled;
+ if (m_semaphore == 0) m_semaphore = semBCreate(SEM_Q_PRIORITY, SEM_FULL);
+ SetAutomaticMode(false); // kill task when adding a new sensor
+ semTake(m_semaphore, WAIT_FOREVER); // link this instance on the list
+ {
+ m_nextSensor = m_firstSensor;
+ m_firstSensor = this;
+ }
+ semGive(m_semaphore);
+
+ m_counter = new Counter(m_echoChannel); // set up counter for this sensor
+ m_counter->SetMaxPeriod(1.0);
+ m_counter->SetSemiPeriodMode(true);
+ m_counter->Reset();
+ m_counter->Start();
+ m_enabled = true; // make it available for round robin scheduling
+ SetAutomaticMode(originalMode);
+
+ static int instances = 0;
+ instances++;
+ nUsageReporting::report(nUsageReporting::kResourceType_Ultrasonic, instances);
+}
+
+/**
+ * Create an instance of the Ultrasonic Sensor using the default module.
+ * This is designed to supchannel the Daventech SRF04 and Vex ultrasonic sensors. This
+ * constructor assumes that both digital I/O channels are in the default digital module.
+ * @param pingChannel The digital output channel that sends the pulse to initiate the sensor sending
+ * the ping.
+ * @param echoChannel The digital input channel that receives the echo. The length of time that the
+ * echo is high represents the round trip time of the ping, and the distance.
+ * @param units The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(UINT32 pingChannel, UINT32 echoChannel, DistanceUnit units)
+{
+ m_pingChannel = new DigitalOutput(pingChannel);
+ m_echoChannel = new DigitalInput(echoChannel);
+ m_allocatedChannels = true;
+ m_units = units;
+ Initialize();
+}
+
+/**
+ * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo channel and a DigitalOutput
+ * for the ping channel.
+ * @param pingChannel The digital output object that starts the sensor doing a ping. Requires a 10uS pulse to start.
+ * @param echoChannel The digital input object that times the return pulse to determine the range.
+ * @param units The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel, DistanceUnit units)
+{
+ if (pingChannel == NULL || echoChannel == NULL)
+ {
+ wpi_setWPIError(NullParameter);
+ return;
+ }
+ m_allocatedChannels = false;
+ m_pingChannel = pingChannel;
+ m_echoChannel = echoChannel;
+ m_units = units;
+ Initialize();
+}
+
+/**
+ * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo channel and a DigitalOutput
+ * for the ping channel.
+ * @param pingChannel The digital output object that starts the sensor doing a ping. Requires a 10uS pulse to start.
+ * @param echoChannel The digital input object that times the return pulse to determine the range.
+ * @param units The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel, DistanceUnit units)
+{
+ m_allocatedChannels = false;
+ m_pingChannel = &pingChannel;
+ m_echoChannel = &echoChannel;
+ m_units = units;
+ Initialize();
+}
+
+/**
+ * Create an instance of the Ultrasonic sensor using specified modules.
+ * This is designed to supchannel the Daventech SRF04 and Vex ultrasonic sensors. This
+ * constructors takes the channel and module slot for each of the required digital I/O channels.
+ * @param pingModuleNumber The digital module that the pingChannel is on.
+ * @param pingChannel The digital output channel that sends the pulse to initiate the sensor
+ * sending the ping.
+ * @param echoModuleNumber The digital module that the echoChannel is on.
+ * @param echoChannel The digital input channel that receives the echo. The length of time
+ * that the echo is high represents the round trip time of the ping, and the distance.
+ * @param units The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(UINT8 pingModuleNumber, UINT32 pingChannel,
+ UINT8 echoModuleNumber, UINT32 echoChannel, DistanceUnit units)
+{
+ m_pingChannel = new DigitalOutput(pingModuleNumber, pingChannel);
+ m_echoChannel = new DigitalInput(echoModuleNumber, echoChannel);
+ m_allocatedChannels = true;
+ m_units = units;
+ Initialize();
+}
+
+/**
+ * Destructor for the ultrasonic sensor.
+ * Delete the instance of the ultrasonic sensor by freeing the allocated digital channels.
+ * If the system was in automatic mode (round robin), then it is stopped, then started again
+ * after this sensor is removed (provided this wasn't the last sensor).
+ */
+Ultrasonic::~Ultrasonic()
+{
+ bool wasAutomaticMode = m_automaticEnabled;
+ SetAutomaticMode(false);
+ if (m_allocatedChannels)
+ {
+ delete m_pingChannel;
+ delete m_echoChannel;
+ }
+ wpi_assert(m_firstSensor != NULL);
+
+ semTake(m_semaphore, WAIT_FOREVER);
+ {
+ if (this == m_firstSensor)
+ {
+ m_firstSensor = m_nextSensor;
+ if (m_firstSensor == NULL)
+ {
+ SetAutomaticMode(false);
+ }
+ }
+ else
+ {
+ wpi_assert(m_firstSensor->m_nextSensor != NULL);
+ for (Ultrasonic *s = m_firstSensor; s != NULL; s = s->m_nextSensor)
+ {
+ if (this == s->m_nextSensor)
+ {
+ s->m_nextSensor = s->m_nextSensor->m_nextSensor;
+ break;
+ }
+ }
+ }
+ }
+ semGive(m_semaphore);
+ if (m_firstSensor != NULL && wasAutomaticMode)
+ SetAutomaticMode(true);
+}
+
+/**
+ * Turn Automatic mode on/off.
+ * When in Automatic mode, all sensors will fire in round robin, waiting a set
+ * time between each sensor.
+ * @param enabling Set to true if round robin scheduling should start for all the ultrasonic sensors. This
+ * scheduling method assures that the sensors are non-interfering because no two sensors fire at the same time.
+ * If another scheduling algorithm is preffered, it can be implemented by pinging the sensors manually and waiting
+ * for the results to come back.
+ */
+void Ultrasonic::SetAutomaticMode(bool enabling)
+{
+ if (enabling == m_automaticEnabled)
+ return; // ignore the case of no change
+
+ m_automaticEnabled = enabling;
+ if (enabling)
+ {
+ // enabling automatic mode.
+ // Clear all the counters so no data is valid
+ for (Ultrasonic *u = m_firstSensor; u != NULL; u = u->m_nextSensor)
+ {
+ u->m_counter->Reset();
+ }
+ // Start round robin task
+ wpi_assert(m_task.Verify() == false); // should be false since was previously disabled
+ m_task.Start();
+ }
+ else
+ {
+ // disabling automatic mode. Wait for background task to stop running.
+ while (m_task.Verify())
+ Wait(0.15); // just a little longer than the ping time for round-robin to stop
+
+ // clear all the counters (data now invalid) since automatic mode is stopped
+ for (Ultrasonic *u = m_firstSensor; u != NULL; u = u->m_nextSensor)
+ {
+ u->m_counter->Reset();
+ }
+ m_task.Stop();
+ }
+}
+
+/**
+ * Single ping to ultrasonic sensor.
+ * Send out a single ping to the ultrasonic sensor. This only works if automatic (round robin)
+ * mode is disabled. A single ping is sent out, and the counter should count the semi-period
+ * when it comes in. The counter is reset to make the current value invalid.
+ */
+void Ultrasonic::Ping()
+{
+ // TODO: Either assert or disable, not both.
+ wpi_assert(!m_automaticEnabled);
+ SetAutomaticMode(false); // turn off automatic round robin if pinging single sensor
+ m_counter->Reset(); // reset the counter to zero (invalid data now)
+ m_pingChannel->Pulse(kPingTime); // do the ping to start getting a single range
+}
+
+/**
+ * Check if there is a valid range measurement.
+ * The ranges are accumulated in a counter that will increment on each edge of the echo (return)
+ * signal. If the count is not at least 2, then the range has not yet been measured, and is invalid.
+ */
+bool Ultrasonic::IsRangeValid()
+{
+ return m_counter->Get() > 1;
+}
+
+/**
+ * Get the range in inches from the ultrasonic sensor.
+ * @return double Range in inches of the target returned from the ultrasonic sensor. If there is
+ * no valid value yet, i.e. at least one measurement hasn't completed, then return 0.
+ */
+double Ultrasonic::GetRangeInches()
+{
+ if (IsRangeValid())
+ return m_counter->GetPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
+ else
+ return 0;
+}
+
+/**
+ * Get the range in millimeters from the ultrasonic sensor.
+ * @return double Range in millimeters of the target returned by the ultrasonic sensor.
+ * If there is no valid value yet, i.e. at least one measurement hasn't complted, then return 0.
+ */
+double Ultrasonic::GetRangeMM()
+{
+ return GetRangeInches() * 25.4;
+}
+
+/**
+ * Get the range in the current DistanceUnit for the PIDSource base object.
+ *
+ * @return The range in DistanceUnit
+ */
+double Ultrasonic::PIDGet()
+{
+ switch(m_units)
+ {
+ case Ultrasonic::kInches:
+ return GetRangeInches();
+ case Ultrasonic::kMilliMeters:
+ return GetRangeMM();
+ default:
+ return 0.0;
+ }
+}
+
+/**
+ * Set the current DistanceUnit that should be used for the PIDSource base object.
+ *
+ * @param units The DistanceUnit that should be used.
+ */
+void Ultrasonic::SetDistanceUnits(DistanceUnit units)
+{
+ m_units = units;
+}
+
+/**
+ * Get the current DistanceUnit that is used for the PIDSource base object.
+ *
+ * @return The type of DistanceUnit that is being used.
+ */
+Ultrasonic::DistanceUnit Ultrasonic::GetDistanceUnits()
+{
+ return m_units;
+}
diff --git a/aos/externals/WPILib/WPILib/Ultrasonic.h b/aos/externals/WPILib/WPILib/Ultrasonic.h
new file mode 100644
index 0000000..865e601
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Ultrasonic.h
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef ULTRASONIC_H_
+#define ULTRASONIC_H_
+
+#include "SensorBase.h"
+#include "Task.h"
+#include "PIDSource.h"
+
+class Counter;
+class DigitalInput;
+class DigitalOutput;
+
+/**
+ * Ultrasonic rangefinder class.
+ * The Ultrasonic rangefinder measures absolute distance based on the round-trip time
+ * of a ping generated by the controller. These sensors use two transducers, a speaker and
+ * a microphone both tuned to the ultrasonic range. A common ultrasonic sensor, the Daventech SRF04
+ * requires a short pulse to be generated on a digital channel. This causes the chirp to be
+ * emmitted. A second line becomes high as the ping is transmitted and goes low when
+ * the echo is received. The time that the line is high determines the round trip distance
+ * (time of flight).
+ */
+class Ultrasonic: public SensorBase, public PIDSource
+{
+public:
+ typedef enum {
+ kInches = 0,
+ kMilliMeters = 1
+ } DistanceUnit;
+
+ Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel, DistanceUnit units = kInches);
+ Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel, DistanceUnit units = kInches);
+ Ultrasonic(UINT32 pingChannel, UINT32 echoChannel, DistanceUnit units = kInches);
+ Ultrasonic(UINT8 pingModuleNumber, UINT32 pingChannel,
+ UINT8 echoModuleNumber, UINT32 echoChannel, DistanceUnit units = kInches);
+ virtual ~Ultrasonic();
+
+ void Ping();
+ bool IsRangeValid();
+ static void SetAutomaticMode(bool enabling);
+ double GetRangeInches();
+ double GetRangeMM();
+ bool IsEnabled() { return m_enabled; }
+ void SetEnabled(bool enable) { m_enabled = enable; }
+
+ double PIDGet();
+ void SetDistanceUnits(DistanceUnit units);
+ DistanceUnit GetDistanceUnits();
+
+private:
+ void Initialize();
+
+ static void UltrasonicChecker();
+
+ static const double kPingTime = 10 * 1e-6; ///< Time (sec) for the ping trigger pulse.
+ static const UINT32 kPriority = 90; ///< Priority that the ultrasonic round robin task runs.
+ static const double kMaxUltrasonicTime = 0.1; ///< Max time (ms) between readings.
+ static const double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
+
+ static Task m_task; // task doing the round-robin automatic sensing
+ static Ultrasonic *m_firstSensor; // head of the ultrasonic sensor list
+ static bool m_automaticEnabled; // automatic round robin mode
+ static SEM_ID m_semaphore; // synchronize access to the list of sensors
+
+ DigitalInput *m_echoChannel;
+ DigitalOutput *m_pingChannel;
+ bool m_allocatedChannels;
+ bool m_enabled;
+ Counter *m_counter;
+ Ultrasonic *m_nextSensor;
+
+ DistanceUnit m_units;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Utility.cpp b/aos/externals/WPILib/WPILib/Utility.cpp
new file mode 100644
index 0000000..5ce84f9
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Utility.cpp
@@ -0,0 +1,438 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Utility.h"
+
+#include "NetworkCommunication/FRCComm.h"
+#include "ChipObject.h"
+#include "Task.h"
+#include <dbgLib.h>
+#include <stdio.h>
+#include <sysSymTbl.h>
+#include "nivision.h"
+
+#define DBG_DEMANGLE_PRINT_LEN 256 /* Num chars of demangled names to print */
+
+extern "C"
+{
+ extern char * cplusDemangle (char *source, char *dest, INT32 n);
+}
+
+char *wpi_getLabel(UINT addr, INT32 *found)
+{
+ INT32 pVal;
+ SYM_TYPE pType;
+ char name[MAX_SYS_SYM_LEN + 1];
+ static char label[DBG_DEMANGLE_PRINT_LEN + 1 + 11];
+ bzero(label, DBG_DEMANGLE_PRINT_LEN + 1 + 11);
+
+ if (symFindByValue(sysSymTbl, addr, name, &pVal, &pType) == OK)
+ {
+ cplusDemangle(name, label, sizeof(label) - 11);
+ if ((UINT)pVal != addr)
+ {
+ sprintf(&label[strlen(label)], "+0x%04x", addr-pVal);
+ if (found) *found = 2;
+ }
+ else
+ {
+ if (found) *found = 1;
+ }
+ }
+ else
+ {
+ sprintf(label, "0x%04x", addr);
+ if (found) *found = 0;
+ }
+
+ return label;
+}
+/*
+static void wpiTracePrint(INSTR *caller, INT32 func, INT32 nargs, INT32 *args, INT32 taskId, BOOL isKernelAdrs)
+{
+ char buf [MAX_SYS_SYM_LEN * 2];
+ INT32 ix;
+ INT32 len = 0;
+ len += sprintf (&buf [len], "%s <%#010x>: ", wpi_getLabel((UINT)caller), (INT32)caller);
+ len += sprintf (&buf [len], "%s <%#010x> (", wpi_getLabel((UINT)func), func);
+ for (ix = 0; ix < nargs; ix++)
+ {
+ if (ix != 0)
+ len += sprintf (&buf [len], ", ");
+ len += sprintf (&buf [len], "%#x", args [ix]);
+ }
+ len += sprintf (&buf [len], ")\n");
+
+ printf(buf);
+}
+*/
+static void wpiCleanTracePrint(INSTR *caller, INT32 func, INT32 nargs, INT32 *args, INT32 taskId, BOOL isKernelAdrs)
+{
+ char buf [MAX_SYS_SYM_LEN];
+ INT32 ix;
+ INT32 len = 0;
+ INT32 nameFound = 0;
+ INT32 params = 0;
+ INT32 totalnargs = nargs;
+ char *funcName = wpi_getLabel((UINT)func, &nameFound);
+ // Ignore names that are not exact symbol address matches.
+ if (nameFound != 1) return;
+
+ // Ignore internal function name matches.
+ if (strncmp(funcName, "wpi_assert", 10) == 0) return;
+ if (strncmp(funcName, "wpi_fatal", 9) == 0) return;
+ if (strncmp(funcName, "wpi_selfTrace", 13) == 0) return;
+ if (strncmp(funcName, "Error::Set", 10) == 0) return;
+ if (strncmp(funcName, "ErrorBase::SetError", 19) == 0) return;
+ if (strncmp(funcName, "Error::Report", 13) == 0) return;
+
+ // Find the number of arguments in the name string.
+ char *start = strchr(funcName, '(');
+ char *end = strrchr(funcName, ')');
+ if (start + 1 != end && start != NULL)
+ {
+ do
+ {
+ params++;
+ if(strncmp(start+1, "bool", 4) == 0 || strncmp(start+2, "bool", 4) == 0)
+ {
+ totalnargs++;
+ }
+ start = strchr(start + 1, ',');
+ }
+ while(start < end && start != NULL);
+ }
+ char *funcNameEnd = strchr(funcName, '(');
+ *funcNameEnd = 0;
+ len += sprintf (&buf [len], funcName);
+
+ // If this is a member function, print out the this pointer value.
+ if (totalnargs - params == 1)
+ {
+ len += sprintf (&buf [len], "<this=%#x>", args [0]);
+ }
+
+ // Print out the argument values.
+ len += sprintf (&buf [len], "(");
+ for (ix = totalnargs - params; ix < nargs; ix++)
+ {
+ if (ix != totalnargs - params)
+ len += sprintf (&buf [len], ", ");
+ len += sprintf (&buf [len], "%#x", args [ix]);
+ }
+ len += sprintf (&buf [len], ")\n");
+
+ printf(buf);
+}
+
+extern "C"
+{
+ extern void trcStack(REG_SET* pRegs, FUNCPTR printRtn, INT32 tid);
+}
+
+static INT32 wpiStackTask(INT32 taskId)
+{
+ taskDelay(1);
+ //tt(taskId);
+
+ REG_SET regs;
+ taskRegsGet(taskId, ®s);
+ trcStack(®s, (FUNCPTR) wpiCleanTracePrint, taskId);
+ printf("\n");
+
+ // The task should be resumed because it had to be suspended to get the stack trace.
+ taskResume(taskId);
+ return 0;
+}
+
+void wpi_selfTrace()
+{
+ INT32 priority=100;
+ taskPriorityGet(0, &priority);
+ // Lower priority than the calling task.
+ Task traceTask("StackTrace", (FUNCPTR)wpiStackTask, priority + 1);
+ traceTask.Start(taskIdSelf());
+
+ // Task to be traced must be suspended for the stack trace to work.
+ taskSuspend(0);
+}
+
+static bool stackTraceEnabled = false;
+static bool suspendOnAssertEnabled = false;
+
+/**
+ * Enable Stack trace after asserts.
+ */
+void wpi_stackTraceOnAssertEnable(bool enabled)
+{
+ stackTraceEnabled = enabled;
+}
+
+/**
+ * Enable suspend on asssert.
+ * If enabled, the user task will be suspended whenever an assert fails. This
+ * will allow the user to attach to the task with the debugger and examine variables
+ * around the failure.
+ */
+void wpi_suspendOnAssertEnabled(bool enabled)
+{
+ suspendOnAssertEnabled = enabled;
+}
+
+static void wpi_handleTracing()
+{
+ if (stackTraceEnabled)
+ {
+ printf("\n-----------<Stack Trace>----------------\n");
+ wpi_selfTrace();
+ }
+ printf("\n");
+}
+
+/**
+ * Assert implementation.
+ * This allows breakpoints to be set on an assert.
+ * The users don't call this, but instead use the wpi_assert macros in Utility.h.
+ */
+bool wpi_assert_impl(bool conditionValue,
+ const char *conditionText,
+ const char *message,
+ const char *fileName,
+ UINT32 lineNumber,
+ const char *funcName)
+{
+ if (!conditionValue)
+ {
+ // Error string buffer
+ char error[256];
+
+ // If an error message was specified, include it
+ // Build error string
+ if(message != NULL) {
+ sprintf(error, "Assertion failed: \"%s\", \"%s\" failed in %s() in %s at line %d\n",
+ message, conditionText, funcName, fileName, lineNumber);
+ } else {
+ sprintf(error, "Assertion failed: \"%s\" in %s() in %s at line %d\n",
+ conditionText, funcName, fileName, lineNumber);
+ }
+
+ // Print to console and send to remote dashboard
+ printf("\n\n>>>>%s", error);
+ setErrorData(error, strlen(error), 100);
+
+ wpi_handleTracing();
+ if (suspendOnAssertEnabled) taskSuspend(0);
+ }
+ return conditionValue;
+}
+
+/**
+ * Common error routines for wpi_assertEqual_impl and wpi_assertNotEqual_impl
+ * This should not be called directly; it should only be used by wpi_assertEqual_impl
+ * and wpi_assertNotEqual_impl.
+ */
+void wpi_assertEqual_common_impl(int valueA,
+ int valueB,
+ const char *equalityType,
+ const char *message,
+ const char *fileName,
+ UINT32 lineNumber,
+ const char *funcName)
+{
+ // Error string buffer
+ char error[256];
+
+ // If an error message was specified, include it
+ // Build error string
+ if(message != NULL) {
+ sprintf(error, "Assertion failed: \"%s\", \"%d\" %s \"%d\" in %s() in %s at line %d\n",
+ message, valueA, equalityType, valueB, funcName, fileName, lineNumber);
+ } else {
+ sprintf(error, "Assertion failed: \"%d\" %s \"%d\" in %s() in %s at line %d\n",
+ valueA, equalityType, valueB, funcName, fileName, lineNumber);
+ }
+
+ // Print to console and send to remote dashboard
+ printf("\n\n>>>>%s", error);
+ setErrorData(error, strlen(error), 100);
+
+ wpi_handleTracing();
+ if (suspendOnAssertEnabled) taskSuspend(0);
+}
+
+/**
+ * Assert equal implementation.
+ * This determines whether the two given integers are equal. If not,
+ * the value of each is printed along with an optional message string.
+ * The users don't call this, but instead use the wpi_assertEqual macros in Utility.h.
+ */
+bool wpi_assertEqual_impl(int valueA,
+ int valueB,
+ const char *message,
+ const char *fileName,
+ UINT32 lineNumber,
+ const char *funcName)
+{
+ if(!(valueA == valueB))
+ {
+ wpi_assertEqual_common_impl(valueA, valueB, "!=", message, fileName, lineNumber, funcName);
+ }
+ return valueA == valueB;
+}
+
+/**
+ * Assert not equal implementation.
+ * This determines whether the two given integers are equal. If so,
+ * the value of each is printed along with an optional message string.
+ * The users don't call this, but instead use the wpi_assertNotEqual macros in Utility.h.
+ */
+bool wpi_assertNotEqual_impl(int valueA,
+ int valueB,
+ const char *message,
+ const char *fileName,
+ UINT32 lineNumber,
+ const char *funcName)
+{
+ if(!(valueA != valueB))
+ {
+ wpi_assertEqual_common_impl(valueA, valueB, "==", message, fileName, lineNumber, funcName);
+ }
+ return valueA != valueB;
+}
+
+
+/**
+ * Return the FPGA Version number.
+ * For now, expect this to be competition year.
+ * @return FPGA Version number.
+ */
+UINT16 GetFPGAVersion()
+{
+ tRioStatusCode status = 0;
+ tGlobal *global = tGlobal::create(&status);
+ UINT16 version = global->readVersion(&status);
+ delete global;
+ wpi_setGlobalError(status);
+ return version;
+}
+
+/**
+ * Return the FPGA Revision number.
+ * The format of the revision is 3 numbers.
+ * The 12 most significant bits are the Major Revision.
+ * the next 8 bits are the Minor Revision.
+ * The 12 least significant bits are the Build Number.
+ * @return FPGA Revision number.
+ */
+UINT32 GetFPGARevision()
+{
+ tRioStatusCode status = 0;
+ tGlobal *global = tGlobal::create(&status);
+ UINT32 revision = global->readRevision(&status);
+ delete global;
+ wpi_setGlobalError(status);
+ return revision;
+}
+
+/**
+ * Read the microsecond-resolution timer on the FPGA.
+ *
+ * @return The current time in microseconds according to the FPGA (since FPGA reset).
+ */
+UINT32 GetFPGATime()
+{
+ tRioStatusCode status = 0;
+ tGlobal *global = tGlobal::create(&status);
+ UINT32 time = global->readLocalTime(&status);
+ delete global;
+ wpi_setGlobalError(status);
+ return time;
+}
+
+// RT hardware access functions exported from ni_emb.out
+extern "C"
+{
+ INT32 UserSwitchInput(INT32 nSwitch);
+ INT32 LedInput(INT32 led);
+ INT32 LedOutput(INT32 led, INT32 value);
+}
+
+/**
+ * Read the value of the USER1 DIP switch on the cRIO.
+ */
+INT32 GetRIOUserSwitch()
+{
+ INT32 switchValue = UserSwitchInput(0);
+ wpi_assert(switchValue >= 0);
+ return switchValue > 0;
+}
+
+/**
+ * Set the state of the USER1 status LED on the cRIO.
+ */
+void SetRIOUserLED(UINT32 state)
+{
+ LedOutput(0, state > 0);
+}
+
+/**
+ * Get the current state of the USER1 status LED on the cRIO.
+ * @return The curent state of the USER1 LED.
+ */
+INT32 GetRIOUserLED()
+{
+ return LedInput(0);
+}
+
+/**
+ * Toggle the state of the USER1 status LED on the cRIO.
+ * @return The new state of the USER1 LED.
+ */
+INT32 ToggleRIOUserLED()
+{
+ INT32 ledState = !GetRIOUserLED();
+ SetRIOUserLED(ledState);
+ return ledState;
+}
+
+/**
+ * Set the state of the FPGA status LED on the cRIO.
+ */
+void SetRIO_FPGA_LED(UINT32 state)
+{
+ tRioStatusCode status = 0;
+ tGlobal *global = tGlobal::create(&status);
+ global->writeFPGA_LED(state, &status);
+ wpi_setGlobalError(status);
+ delete global;
+}
+
+/**
+ * Get the current state of the FPGA status LED on the cRIO.
+ * @return The curent state of the FPGA LED.
+ */
+INT32 GetRIO_FPGA_LED()
+{
+ tRioStatusCode status = 0;
+ tGlobal *global = tGlobal::create(&status);
+ bool ledValue = global->readFPGA_LED(&status);
+ wpi_setGlobalError(status);
+ delete global;
+ return ledValue;
+}
+
+/**
+ * Toggle the state of the FPGA status LED on the cRIO.
+ * @return The new state of the FPGA LED.
+ */
+INT32 ToggleRIO_FPGA_LED()
+{
+ INT32 ledState = !GetRIO_FPGA_LED();
+ SetRIO_FPGA_LED(ledState);
+ return ledState;
+}
+
+
diff --git a/aos/externals/WPILib/WPILib/Utility.h b/aos/externals/WPILib/WPILib/Utility.h
new file mode 100644
index 0000000..01bcbff
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Utility.h
@@ -0,0 +1,41 @@
+/*---------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*---------------------------------------------------------------------------*/
+
+#ifndef UTILITY_H_
+#define UTILITY_H_
+
+#include <taskLib.h>
+
+#define wpi_assert(condition) wpi_assert_impl(condition, #condition, NULL, __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertWithMessage(condition, message) wpi_assert_impl(condition, #condition, message, __FILE__, __LINE__, __FUNCTION__)
+
+#define wpi_assertEqual(a, b) wpi_assertEqual_impl(a, b, NULL, __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertEqualWithMessage(a, b, message) wpi_assertEqual_impl(a, b, message, __FILE__, __LINE__, __FUNCTION__)
+
+#define wpi_assertNotEqual(a, b) wpi_assertNotEqual_impl(a, b, NULL, __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertNotEqualWithMessage(a, b, message) wpi_assertNotEqual_impl(a, b, message, __FILE__, __LINE__, __FUNCTION__)
+
+bool wpi_assert_impl(bool conditionValue, const char *conditionText, const char *message, const char *fileName, UINT32 lineNumber, const char *funcName);
+bool wpi_assertEqual_impl(int valueA, int valueB, const char *message, const char *fileName,UINT32 lineNumber, const char *funcName);
+bool wpi_assertNotEqual_impl(int valueA, int valueB, const char *message, const char *fileName,UINT32 lineNumber, const char *funcName);
+
+char *wpi_getLabel(UINT addr, INT32 *found = NULL);
+void wpi_selfTrace();
+void wpi_suspendOnAssertEnabled(bool enabled);
+void wpi_stackTraceOnAssertEnable(bool enabled);
+
+UINT16 GetFPGAVersion();
+UINT32 GetFPGARevision();
+UINT32 GetFPGATime();
+INT32 GetRIOUserSwitch();
+void SetRIOUserLED(UINT32 state);
+INT32 GetRIOUserLED();
+INT32 ToggleRIOUserLED();
+void SetRIO_FPGA_LED(UINT32 state);
+INT32 GetRIO_FPGA_LED();
+INT32 ToggleRIO_FPGA_LED();
+
+#endif // UTILITY_H_
diff --git a/aos/externals/WPILib/WPILib/Victor.cpp b/aos/externals/WPILib/WPILib/Victor.cpp
new file mode 100644
index 0000000..4dc71ed
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Victor.cpp
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Victor.h"
+
+#include "DigitalModule.h"
+#include "NetworkCommunication/UsageReporting.h"
+
+/**
+ * Common initialization code called by all constructors.
+ *
+ * Note that the Victor uses the following bounds for PWM values. These values were determined
+ * empirically through experimentation during the 2008 beta testing of the new control system.
+ * Testing during the beta period revealed a significant amount of variation between Victors.
+ * The values below are chosen to ensure that teams using the default values should be able to
+ * get "full power" with the maximum and minimum values. For better performance, teams may wish
+ * to measure these values on their own Victors and set the bounds to the particular values
+ * measured for the actual Victors they were be using.
+ * - 210 = full "forward"
+ * - 138 = the "high end" of the deadband range
+ * - 132 = center of the deadband range (off)
+ * - 126 = the "low end" of the deadband range
+ * - 56 = full "reverse"
+ */
+void Victor::InitVictor()
+{
+ // TODO: compute the appropriate values based on digital loop timing
+ SetBounds(210, 138, 132, 126, 56);
+ SetPeriodMultiplier(kPeriodMultiplier_2X);
+ SetRaw(m_centerPwm);
+
+ nUsageReporting::report(nUsageReporting::kResourceType_Victor, GetChannel(), GetModuleNumber() - 1);
+}
+
+/**
+ * Constructor that assumes the default digital module.
+ *
+ * @param channel The PWM channel on the digital module that the Victor is attached to.
+ */
+Victor::Victor(UINT32 channel) : SafePWM(channel)
+{
+ InitVictor();
+}
+
+/**
+ * Constructor that specifies the digital module.
+ *
+ * @param moduleNumber The digital module (1 or 2).
+ * @param channel The PWM channel on the digital module that the Victor is attached to (1..10).
+ */
+Victor::Victor(UINT8 moduleNumber, UINT32 channel) : SafePWM(moduleNumber, channel)
+{
+ InitVictor();
+}
+
+Victor::~Victor()
+{
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ * @param syncGroup Unused interface.
+ */
+void Victor::Set(float speed, UINT8 syncGroup)
+{
+ SetSpeed(speed);
+}
+
+/**
+ * Get the recently set value of the PWM.
+ *
+ * @return The most recently set value for the PWM between -1.0 and 1.0.
+ */
+float Victor::Get()
+{
+ return GetSpeed();
+}
+
+/**
+ * Common interface for disabling a motor.
+ */
+void Victor::Disable()
+{
+ SetRaw(kPwmDisabled);
+}
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @param output Write out the PWM value as was found in the PIDController
+ */
+void Victor::PIDWrite(float output)
+{
+ Set(output);
+}
+
diff --git a/aos/externals/WPILib/WPILib/Victor.h b/aos/externals/WPILib/WPILib/Victor.h
new file mode 100644
index 0000000..1821631
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Victor.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef VICTOR_H
+#define VICTOR_H
+
+#include "SafePWM.h"
+#include "SpeedController.h"
+#include "PIDOutput.h"
+
+/**
+ * IFI Victor Speed Controller
+ */
+class Victor : public SafePWM, public SpeedController, public PIDOutput
+{
+public:
+ explicit Victor(UINT32 channel);
+ Victor(UINT8 moduleNumber, UINT32 channel);
+ virtual ~Victor();
+ virtual void Set(float value, UINT8 syncGroup=0);
+ virtual float Get();
+ virtual void Disable();
+
+ virtual void PIDWrite(float output);
+
+private:
+ void InitVictor();
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Vision/AxisCamera.cpp b/aos/externals/WPILib/WPILib/Vision/AxisCamera.cpp
new file mode 100644
index 0000000..7cd20f4
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/AxisCamera.cpp
@@ -0,0 +1,501 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Vision/AxisCamera.h"
+
+#include <string.h>
+#include "NetworkCommunication/UsageReporting.h"
+#include "Synchronized.h"
+#include "Vision/PCVideoServer.h"
+#include "WPIErrors.h"
+
+/** Private NI function to decode JPEG */
+IMAQ_FUNC int Priv_ReadJPEGString_C(Image* _image, const unsigned char* _string, UINT32 _stringLength);
+
+// Max packet without jumbo frames is 1500... add 36 because??
+#define kMaxPacketSize 1536
+#define kImageBufferAllocationIncrement 1000
+
+AxisCamera *AxisCamera::_instance = NULL;
+
+/**
+ * AxisCamera constructor
+ */
+AxisCamera::AxisCamera(const char *ipAddress)
+ : AxisCameraParams(ipAddress)
+ , m_cameraSocket(ERROR)
+ , m_protectedImageBuffer(NULL)
+ , m_protectedImageBufferLength(0)
+ , m_protectedImageSize(0)
+ , m_protectedImageSem(NULL)
+ , m_freshImage(false)
+ , m_imageStreamTask("cameraTask", (FUNCPTR)s_ImageStreamTaskFunction)
+ , m_videoServer(NULL)
+{
+ m_protectedImageSem = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE | SEM_DELETE_SAFE);
+
+#if JAVA_CAMERA_LIB != 1
+ nUsageReporting::report(nUsageReporting::kResourceType_AxisCamera, ipAddress == NULL ? 1 : 2);
+#endif
+
+ if (!StatusIsFatal())
+ m_imageStreamTask.Start((int)this);
+}
+
+/**
+ * Destructor
+ */
+AxisCamera::~AxisCamera()
+{
+ delete m_videoServer;
+ m_videoServer = NULL;
+
+ m_imageStreamTask.Stop();
+ close(m_cameraSocket);
+
+ SemSet_t::iterator it = m_newImageSemSet.begin();
+ SemSet_t::iterator end = m_newImageSemSet.end();
+ for (;it != end; it++)
+ {
+ semDelete(*it);
+ }
+ m_newImageSemSet.clear();
+
+ semDelete(m_protectedImageSem);
+}
+
+/**
+ * Get a pointer to the AxisCamera object, if the object does not exist, create it
+ * To use the camera on port 2 of a cRIO-FRC, pass "192.168.0.90" to the first GetInstance call.
+ * @return reference to AxisCamera object
+ */
+AxisCamera &AxisCamera::GetInstance(const char *cameraIP)
+{
+ if (NULL == _instance)
+ {
+ _instance = new AxisCamera(cameraIP);
+
+ _instance->m_videoServer = new PCVideoServer();
+ }
+
+ return *_instance;
+}
+
+/**
+ * Called by Java to delete the camera... how thoughtful
+ */
+void AxisCamera::DeleteInstance()
+{
+ delete _instance;
+ _instance = NULL;
+}
+
+/**
+ * Return true if the latest image from the camera has not been retrieved by calling GetImage() yet.
+ * @return true if the image has not been retrieved yet.
+ */
+bool AxisCamera::IsFreshImage()
+{
+ return m_freshImage;
+}
+
+/**
+ * Get the semaphore to be used to synchronize image access with camera acquisition
+ *
+ * Call semTake on the returned semaphore to block until a new image is acquired.
+ *
+ * The semaphore is owned by the AxisCamera class and will be deleted when the class is destroyed.
+ * @return A semaphore to notify when new image is received
+ */
+SEM_ID AxisCamera::GetNewImageSem()
+{
+ SEM_ID sem = semBCreate (SEM_Q_PRIORITY, SEM_EMPTY);
+ m_newImageSemSet.insert(sem);
+ return sem;
+}
+
+/**
+ * Get an image from the camera and store it in the provided image.
+ * @param image The imaq image to store the result in. This must be an HSL or RGB image
+ * This function is called by Java.
+ * @return 1 upon success, zero on a failure
+ */
+int AxisCamera::GetImage(Image* imaqImage)
+{
+ if (m_protectedImageBuffer == NULL)
+ return 0;
+ Synchronized sync(m_protectedImageSem);
+ Priv_ReadJPEGString_C(imaqImage,
+ (unsigned char*)m_protectedImageBuffer, m_protectedImageSize);
+ m_freshImage = false;
+ return 1;
+}
+
+#if JAVA_CAMERA_LIB != 1
+/**
+ * Get an image from the camera and store it in the provided image.
+ * @param image The image to store the result in. This must be an HSL or RGB image
+ * @return 1 upon success, zero on a failure
+ */
+int AxisCamera::GetImage(ColorImage* image)
+{
+ return GetImage(image->GetImaqImage());
+}
+
+/**
+ * Instantiate a new image object and fill it with the latest image from the camera.
+ *
+ * The returned pointer is owned by the caller and is their responsibility to delete.
+ * @return a pointer to an HSLImage object
+ */
+HSLImage* AxisCamera::GetImage()
+{
+ HSLImage *image = new HSLImage();
+ GetImage(image);
+ return image;
+}
+#endif
+
+/**
+ * Copy an image into an existing buffer.
+ * This copies an image into an existing buffer rather than creating a new image
+ * in memory. That way a new image is only allocated when the image being copied is
+ * larger than the destination.
+ * This method is called by the PCVideoServer class.
+ * @param imageData The destination image.
+ * @param numBytes The size of the destination image.
+ * @return 0 if failed (no source image or no memory), 1 if success.
+ */
+int AxisCamera::CopyJPEG(char **destImage, int &destImageSize, int &destImageBufferSize)
+{
+ Synchronized sync(m_protectedImageSem);
+ if (destImage == NULL)
+ wpi_setWPIErrorWithContext(NullParameter, "destImage must not be NULL");
+
+ if (m_protectedImageBuffer == NULL || m_protectedImageSize <= 0)
+ return 0; // if no source image
+
+ if (destImageBufferSize < m_protectedImageSize) // if current destination buffer too small
+ {
+ if (*destImage != NULL) delete [] *destImage;
+ destImageBufferSize = m_protectedImageSize + kImageBufferAllocationIncrement;
+ *destImage = new char[destImageBufferSize];
+ if (*destImage == NULL) return 0;
+ }
+ // copy this image into destination buffer
+ if (*destImage == NULL)
+ {
+ wpi_setWPIErrorWithContext(NullParameter, "*destImage must not be NULL");
+ }
+ // TODO: Is this copy realy necessary... perhaps we can simply transmit while holding the protected buffer
+ memcpy(*destImage, m_protectedImageBuffer, m_protectedImageSize);
+ destImageSize = m_protectedImageSize;
+ return 1;
+}
+
+/**
+ * Static interface that will cause an instantiation if necessary.
+ * This static stub is directly spawned as a task to read images from the camera.
+ */
+int AxisCamera::s_ImageStreamTaskFunction(AxisCamera *thisPtr)
+{
+ return thisPtr->ImageStreamTaskFunction();
+}
+
+/**
+ * Task spawned by AxisCamera constructor to receive images from cam
+ * If setNewImageSem has been called, this function does a semGive on each new image
+ * Images can be accessed by calling getImage()
+ */
+int AxisCamera::ImageStreamTaskFunction()
+{
+ // Loop on trying to setup the camera connection. This happens in a background
+ // thread so it shouldn't effect the operation of user programs.
+ while (1)
+ {
+ const char *requestString = "GET /mjpg/video.mjpg HTTP/1.1\n\
+User-Agent: HTTPStreamClient\n\
+Connection: Keep-Alive\n\
+Cache-Control: no-cache\n\
+Authorization: Basic RlJDOkZSQw==\n\n";
+ semTake(m_socketPossessionSem, WAIT_FOREVER);
+ m_cameraSocket = CreateCameraSocket(requestString);
+ if (m_cameraSocket == ERROR)
+ {
+ // Don't hammer the camera if it isn't ready.
+ semGive(m_socketPossessionSem);
+ taskDelay(1000);
+ }
+ else
+ {
+ ReadImagesFromCamera();
+ }
+ }
+}
+
+/**
+ * This function actually reads the images from the camera.
+ */
+int AxisCamera::ReadImagesFromCamera()
+{
+ char *imgBuffer = NULL;
+ int imgBufferLength = 0;
+ //Infinite loop, task deletion handled by taskDeleteHook
+ // Socket cleanup handled by destructor
+
+ // TODO: these recv calls must be non-blocking. Otherwise if the camera
+ // fails during a read, the code hangs and never retries when the camera comes
+ // back up.
+
+ int counter = 2;
+ while (1)
+ {
+ char initialReadBuffer[kMaxPacketSize] = "";
+ char intermediateBuffer[1];
+ char *trailingPtr = initialReadBuffer;
+ int trailingCounter = 0;
+ while (counter)
+ {
+ // TODO: fix me... this cannot be the most efficient way to approach this, reading one byte at a time.
+ if(recv(m_cameraSocket, intermediateBuffer, 1, 0) == ERROR)
+ {
+ wpi_setErrnoErrorWithContext("Failed to read image header");
+ close (m_cameraSocket);
+ return ERROR;
+ }
+ strncat(initialReadBuffer, intermediateBuffer, 1);
+ // trailingCounter ensures that we start looking for the 4 byte string after
+ // there is at least 4 bytes total. Kind of obscure.
+ // look for 2 blank lines (\r\n)
+ if (NULL != strstr(trailingPtr, "\r\n\r\n"))
+ {
+ --counter;
+ }
+ if (++trailingCounter >= 4)
+ {
+ trailingPtr++;
+ }
+ }
+ counter = 1;
+ char *contentLength = strstr(initialReadBuffer, "Content-Length: ");
+ if (contentLength == NULL)
+ {
+ wpi_setWPIErrorWithContext(IncompatibleMode, "No content-length token found in packet");
+ close(m_cameraSocket);
+ return ERROR;
+ }
+ contentLength = contentLength + 16; // skip past "content length"
+ int readLength = atol(contentLength); // get the image byte count
+
+ // Make sure buffer is large enough
+ if (imgBufferLength < readLength)
+ {
+ if (imgBuffer) delete[] imgBuffer;
+ imgBufferLength = readLength + kImageBufferAllocationIncrement;
+ imgBuffer = new char[imgBufferLength];
+ if (imgBuffer == NULL)
+ {
+ imgBufferLength = 0;
+ continue;
+ }
+ }
+
+ // Read the image data for "Content-Length" bytes
+ int bytesRead = 0;
+ int remaining = readLength;
+ while(bytesRead < readLength)
+ {
+ int bytesThisRecv = recv(m_cameraSocket, &imgBuffer[bytesRead], remaining, 0);
+ bytesRead += bytesThisRecv;
+ remaining -= bytesThisRecv;
+ }
+ // Update image
+ UpdatePublicImageFromCamera(imgBuffer, readLength);
+ if (semTake(m_paramChangedSem, NO_WAIT) == OK)
+ {
+ // params need to be updated: close the video stream; release the camera.
+ close(m_cameraSocket);
+ semGive(m_socketPossessionSem);
+ return 0;
+ }
+ }
+}
+
+/**
+ * Copy the image from private buffer to shared buffer.
+ * @param imgBuffer The buffer containing the image
+ * @param bufLength The length of the image
+ */
+void AxisCamera::UpdatePublicImageFromCamera(char *imgBuffer, int imgSize)
+{
+ {
+ Synchronized sync(m_protectedImageSem);
+
+ // Adjust the buffer size if current destination buffer is too small.
+ if (m_protectedImageBufferLength < imgSize)
+ {
+ if (m_protectedImageBuffer != NULL) delete [] m_protectedImageBuffer;
+ m_protectedImageBufferLength = imgSize + kImageBufferAllocationIncrement;
+ m_protectedImageBuffer = new char[m_protectedImageBufferLength];
+ if (m_protectedImageBuffer == NULL)
+ {
+ m_protectedImageBufferLength = 0;
+ return;
+ }
+ }
+
+ memcpy(m_protectedImageBuffer, imgBuffer, imgSize);
+ m_protectedImageSize = imgSize;
+ }
+
+ m_freshImage = true;
+ // Notify everyone who is interested.
+ SemSet_t::iterator it = m_newImageSemSet.begin();
+ SemSet_t::iterator end = m_newImageSemSet.end();
+ for (;it != end; it++)
+ {
+ semGive(*it);
+ }
+}
+
+/**
+ * Implement the pure virtual interface so that when parameter changes require a restart, the image task can be bounced.
+ */
+void AxisCamera::RestartCameraTask()
+{
+ m_imageStreamTask.Stop();
+ m_imageStreamTask.Start((int)this);
+}
+
+#if JAVA_CAMERA_LIB == 1
+
+// C bindings used by Java
+// These need to stay as is or Java has to change
+
+void AxisCameraStart(const char *IPAddress)
+{
+#ifdef SVN_REV
+ if (strlen(SVN_REV))
+ {
+ printf("JavaCameraLib was compiled from SVN revision %s\n", SVN_REV);
+ }
+ else
+ {
+ printf("JavaCameraLib was compiled from a location that is not source controlled.\n");
+ }
+#else
+ printf("JavaCameraLib was compiled without -D'SVN_REV=nnnn'\n");
+#endif
+ AxisCamera::GetInstance(IPAddress);
+}
+
+int AxisCameraGetImage (Image* image)
+{
+ return AxisCamera::GetInstance().GetImage(image);
+}
+
+void AxisCameraWriteBrightness(int brightness)
+{
+ AxisCamera::GetInstance().WriteBrightness(brightness);
+}
+
+int AxisCameraGetBrightness()
+{
+ return AxisCamera::GetInstance().GetBrightness();
+}
+
+void AxisCameraWriteWhiteBalance(AxisCameraParams::WhiteBalance_t whiteBalance)
+{
+ AxisCamera::GetInstance().WriteWhiteBalance(whiteBalance);
+}
+
+AxisCameraParams::WhiteBalance_t AxisCameraGetWhiteBalance()
+{
+ return AxisCamera::GetInstance().GetWhiteBalance();
+}
+
+void AxisCameraWriteColorLevel(int colorLevel)
+{
+ AxisCamera::GetInstance().WriteColorLevel(colorLevel);
+}
+
+int AxisCameraGetColorLevel()
+{
+ return AxisCamera::GetInstance().GetColorLevel();
+}
+
+void AxisCameraWriteExposureControl(AxisCameraParams::Exposure_t exposure)
+{
+ AxisCamera::GetInstance().WriteExposureControl(exposure);
+}
+
+AxisCameraParams::Exposure_t AxisCameraGetExposureControl()
+{
+ return AxisCamera::GetInstance().GetExposureControl();
+}
+
+void AxisCameraWriteExposurePriority(int exposure)
+{
+ AxisCamera::GetInstance().WriteExposurePriority(exposure);
+}
+
+int AxisCameraGetExposurePriority()
+{
+ return AxisCamera::GetInstance().GetExposurePriority();
+}
+
+void AxisCameraWriteMaxFPS(int maxFPS)
+{
+ AxisCamera::GetInstance().WriteMaxFPS(maxFPS);
+}
+
+int AxisCameraGetMaxFPS()
+{
+ return AxisCamera::GetInstance().GetMaxFPS();
+}
+
+void AxisCameraWriteResolution(AxisCameraParams::Resolution_t resolution)
+{
+ AxisCamera::GetInstance().WriteResolution(resolution);
+}
+
+AxisCameraParams::Resolution_t AxisCameraGetResolution()
+{
+ return AxisCamera::GetInstance().GetResolution();
+}
+
+void AxisCameraWriteCompression(int compression)
+{
+ AxisCamera::GetInstance().WriteCompression(compression);
+}
+
+int AxisCameraGetCompression()
+{
+ return AxisCamera::GetInstance().GetCompression();
+}
+
+void AxisCameraWriteRotation(AxisCameraParams::Rotation_t rotation)
+{
+ AxisCamera::GetInstance().WriteRotation(rotation);
+}
+
+AxisCameraParams::Rotation_t AxisCameraGetRotation()
+{
+ return AxisCamera::GetInstance().GetRotation();
+}
+
+void AxisCameraDeleteInstance()
+{
+ AxisCamera::DeleteInstance();
+}
+
+int AxisCameraFreshImage()
+{
+ return AxisCamera::GetInstance().IsFreshImage();
+}
+
+#endif // JAVA_CAMERA_LIB == 1
+
diff --git a/aos/externals/WPILib/WPILib/Vision/AxisCamera.h b/aos/externals/WPILib/WPILib/Vision/AxisCamera.h
new file mode 100644
index 0000000..0d96333
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/AxisCamera.h
@@ -0,0 +1,114 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __AXIS_CAMERA_H__
+#define __AXIS_CAMERA_H__
+
+#include <taskLib.h>
+#include <vxWorks.h>
+#include <sockLib.h>
+#include <inetLib.h>
+
+#include "Vision/AxisCameraParams.h"
+#if JAVA_CAMERA_LIB != 1
+#include "Vision/ColorImage.h"
+#include "Vision/HSLImage.h"
+#endif
+#include "nivision.h"
+#include <set>
+#include "Task.h"
+
+class PCVideoServer;
+
+/**
+ * AxisCamera class.
+ * This class handles everything about the Axis 206 FRC Camera.
+ * It starts up 2 tasks each using a different connection to the camera:
+ * - image reading task that reads images repeatedly from the camera
+ * - parameter handler task in the base class that monitors for changes to
+ * parameters and updates the camera
+ */
+class AxisCamera : public AxisCameraParams
+{
+private:
+ explicit AxisCamera(const char *cameraIP);
+public:
+ virtual ~AxisCamera();
+ static AxisCamera& GetInstance(const char *cameraIP = NULL);
+ static void DeleteInstance();
+
+ bool IsFreshImage();
+ SEM_ID GetNewImageSem();
+
+ int GetImage(Image *imaqImage);
+#if JAVA_CAMERA_LIB != 1
+ int GetImage(ColorImage *image);
+ HSLImage *GetImage();
+#endif
+
+ int CopyJPEG(char **destImage, int &destImageSize, int &destImageBufferSize);
+
+private:
+ static int s_ImageStreamTaskFunction(AxisCamera *thisPtr);
+ int ImageStreamTaskFunction();
+
+ int ReadImagesFromCamera();
+ void UpdatePublicImageFromCamera(char *imgBuffer, int imgSize);
+
+ virtual void RestartCameraTask();
+
+ static AxisCamera *_instance;
+ int m_cameraSocket;
+ typedef std::set<SEM_ID> SemSet_t;
+ SemSet_t m_newImageSemSet;
+
+ char* m_protectedImageBuffer;
+ int m_protectedImageBufferLength;
+ int m_protectedImageSize;
+ SEM_ID m_protectedImageSem;
+ bool m_freshImage;
+
+ Task m_imageStreamTask;
+
+ PCVideoServer *m_videoServer;
+};
+
+#if JAVA_CAMERA_LIB == 1
+#ifdef __cplusplus
+extern "C" {
+#endif
+ void AxisCameraStart(const char *IPAddress);
+ int AxisCameraGetImage(Image *image);
+ void AxisCameraDeleteInstance();
+ int AxisCameraFreshImage();
+
+ // Mid-stream gets & writes
+ void AxisCameraWriteBrightness(int brightness);
+ int AxisCameraGetBrightness();
+ void AxisCameraWriteWhiteBalance(AxisCameraParams::WhiteBalance_t whiteBalance);
+ AxisCameraParams::WhiteBalance_t AxisCameraGetWhiteBalance();
+ void AxisCameraWriteColorLevel(int colorLevel);
+ int AxisCameraGetColorLevel();
+ void AxisCameraWriteExposureControl(AxisCameraParams::Exposure_t exposure);
+ AxisCameraParams::Exposure_t AxisCameraGetExposureControl();
+ void AxisCameraWriteExposurePriority(int exposurePriority);
+ int AxisCameraGetExposurePriority();
+ void AxisCameraWriteMaxFPS(int maxFPS);
+ int AxisCameraGetMaxFPS();
+
+ // New-Stream gets & writes
+ void AxisCameraWriteResolution(AxisCameraParams::Resolution_t resolution);
+ AxisCameraParams::Resolution_t AxisCameraGetResolution();
+ void AxisCameraWriteCompression(int compression);
+ int AxisCameraGetCompression();
+ void AxisCameraWriteRotation(AxisCameraParams::Rotation_t rotation);
+ AxisCameraParams::Rotation_t AxisCameraGetRotation();
+#ifdef __cplusplus
+}
+#endif
+#endif // JAVA_CAMERA_LIB == 1
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Vision/AxisCameraParams.cpp b/aos/externals/WPILib/WPILib/Vision/AxisCameraParams.cpp
new file mode 100644
index 0000000..c537271
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/AxisCameraParams.cpp
@@ -0,0 +1,469 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Vision/AxisCameraParams.h"
+
+#include "Vision/AxisCamera.h"
+#include <inetLib.h>
+#include "pcre.h"
+#include <sockLib.h>
+#include <string.h>
+#include "Synchronized.h"
+#include "Timer.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+#if JAVA_CAMERA_LIB != 1
+#include "DriverStation.h"
+#endif
+
+static const char *const kRotationChoices[] = {"0", "180"};
+static const char *const kResolutionChoices[] = {"640x480", "640x360", "320x240", "160x120"};
+static const char *const kExposureControlChoices[] = { "automatic", "hold", "flickerfree50", "flickerfree60" };
+static const char *const kWhiteBalanceChoices[] = { "auto", "holdwb", "fixed_outdoor1",
+ "fixed_outdoor2", "fixed_indoor", "fixed_fluor1", "fixed_fluor2" };
+
+/**
+ * AxisCamera constructor
+ */
+AxisCameraParams::AxisCameraParams(const char* ipAddress)
+ : m_paramTask("paramTask", (FUNCPTR) s_ParamTaskFunction)
+ , m_paramChangedSem (NULL)
+ , m_socketPossessionSem (NULL)
+ , m_brightnessParam (NULL)
+ , m_compressionParam (NULL)
+ , m_exposurePriorityParam (NULL)
+ , m_colorLevelParam (NULL)
+ , m_maxFPSParam (NULL)
+ , m_rotationParam (NULL)
+ , m_resolutionParam (NULL)
+ , m_exposureControlParam (NULL)
+ , m_whiteBalanceParam (NULL)
+{
+ if (ipAddress == NULL || strlen(ipAddress) == 0)
+ {
+#if JAVA_CAMERA_LIB == 1
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "IP Address must be specified");
+ return;
+#else
+ DriverStation *ds = DriverStation::GetInstance();
+ ds->WaitForData();
+ UINT16 teamNumber = ds->GetTeamNumber();
+ char cameraIP[16];
+ snprintf(cameraIP, 16, "10.%d.%d.11", teamNumber / 100, teamNumber % 100);
+ m_ipAddress = inet_addr(cameraIP);
+#endif
+ }
+ else
+ {
+ m_ipAddress = inet_addr((char*)ipAddress);
+ }
+
+ if (m_ipAddress == (u_long)ERROR)
+ {
+ wpi_setErrnoError();
+ return;
+ }
+
+ m_brightnessParam = new IntCameraParameter("ImageSource.I0.Sensor.Brightness=%i",
+ "root.ImageSource.I0.Sensor.Brightness=(.*)", false);
+ m_parameters.push_back(m_brightnessParam);
+ m_colorLevelParam = new IntCameraParameter("ImageSource.I0.Sensor.ColorLevel=%i",
+ "root.ImageSource.I0.Sensor.ColorLevel=(.*)", false);
+ m_parameters.push_back(m_colorLevelParam);
+ m_exposurePriorityParam = new IntCameraParameter("ImageSource.I0.Sensor.exposurePriority=%i",
+ "root.ImageSource.I0.Sensor.ExposurePriority=(.*)", false);
+ m_parameters.push_back(m_exposurePriorityParam);
+ m_compressionParam = new IntCameraParameter("Image.I0.Appearance.Compression=%i",
+ "root.Image.I0.Appearance.Compression=(.*)", true);
+ m_parameters.push_back(m_compressionParam);
+ m_maxFPSParam = new IntCameraParameter("Image.I0.Stream.FPS=%i",
+ "root.Image.I0.Stream.FPS=(.*)", false);
+ m_parameters.push_back(m_maxFPSParam);
+ m_rotationParam = new EnumCameraParameter("Image.I0.Appearance.Rotation=%s",
+ "root.Image.I0.Appearance.Rotation=(.*)", true, kRotationChoices, sizeof(kRotationChoices)/sizeof(kRotationChoices[0]));
+ m_parameters.push_back(m_rotationParam);
+ m_resolutionParam = new EnumCameraParameter("Image.I0.Appearance.Resolution=%s",
+ "root.Image.I0.Appearance.Resolution=(.*)", true, kResolutionChoices, sizeof(kResolutionChoices)/sizeof(kResolutionChoices[0]));
+ m_parameters.push_back(m_resolutionParam);
+ m_exposureControlParam = new EnumCameraParameter("ImageSource.I0.Sensor.Exposure=%s",
+ "root.ImageSource.I0.Sensor.Exposure=(.*)", false, kExposureControlChoices, sizeof(kExposureControlChoices)/sizeof(kExposureControlChoices[0]));
+ m_parameters.push_back(m_exposureControlParam);
+ m_whiteBalanceParam = new EnumCameraParameter("ImageSource.IO.Sensor.WhiteBalance=%s",
+ "root.ImageSource.I0.Sensor.WhiteBalance=(.*)", false, kWhiteBalanceChoices, sizeof(kWhiteBalanceChoices)/sizeof(kWhiteBalanceChoices[0]));
+ m_parameters.push_back(m_whiteBalanceParam);
+
+ m_paramChangedSem = semBCreate (SEM_Q_PRIORITY, SEM_EMPTY);
+ m_socketPossessionSem = semBCreate (SEM_Q_PRIORITY, SEM_FULL);
+
+ m_paramTask.Start((int)this);
+}
+
+/**
+ * Destructor
+ */
+AxisCameraParams::~AxisCameraParams()
+{
+ m_paramTask.Stop();
+
+ semDelete(m_socketPossessionSem);
+ semDelete(m_paramChangedSem);
+
+ delete m_whiteBalanceParam;
+ delete m_exposureControlParam;
+ delete m_resolutionParam;
+ delete m_rotationParam;
+ delete m_maxFPSParam;
+ delete m_compressionParam;
+ delete m_exposurePriorityParam;
+ delete m_colorLevelParam;
+ delete m_brightnessParam;
+}
+
+/**
+ * Static function to start the parameter updating task
+ */
+int AxisCameraParams::s_ParamTaskFunction(AxisCameraParams* thisPtr)
+{
+ return thisPtr->ParamTaskFunction();
+}
+
+/**
+ * Main loop of the parameter task.
+ * This loop runs continuously checking parameters from the camera for
+ * posted changes and updating them if necessary.
+ */
+// TODO: need to synchronize the actual setting of parameters (the assignment statement)
+int AxisCameraParams::ParamTaskFunction()
+{
+ static bool firstTime = true;
+
+ while (true)
+ {
+ semTake(m_socketPossessionSem, WAIT_FOREVER);
+ if (firstTime)
+ {
+ while (ReadCamParams() == 0);
+ firstTime = false;
+ }
+ bool restartRequired = false;
+
+ ParameterVector_t::iterator it = m_parameters.begin();
+ ParameterVector_t::iterator end = m_parameters.end();
+ for(; it != end; it++)
+ {
+ bool changed = false;
+ char param[150];
+ restartRequired |= (*it)->CheckChanged(changed, param);
+ if (changed)
+ {
+ UpdateCamParam(param);
+ }
+ }
+ if (restartRequired)
+ {
+ RestartCameraTask();
+ }
+ semGive(m_socketPossessionSem);
+ }
+ return 0;
+}
+
+/**
+ * Write the brightness value to the camera.
+ * @param brightness valid values 0 .. 100
+ */
+void AxisCameraParams::WriteBrightness(int brightness)
+{
+ m_brightnessParam->SetValue(brightness);
+ semGive(m_paramChangedSem);
+}
+
+/**
+ * Get the brightness value.
+ * @return Brightness value from the camera.
+ */
+int AxisCameraParams::GetBrightness()
+{
+ return m_brightnessParam->GetValue();
+}
+
+/**
+ * Set the white balance value.
+ * @param whiteBalance Valid values from the WhiteBalance_t enum.
+ */
+void AxisCameraParams::WriteWhiteBalance(WhiteBalance_t whiteBalance)
+{
+ m_whiteBalanceParam->SetValue(whiteBalance);
+ semGive(m_paramChangedSem);
+}
+
+/**
+ * Retrieve the current white balance parameter.
+ * @return The white balance value.
+ */
+AxisCameraParams::WhiteBalance_t AxisCameraParams::GetWhiteBalance()
+{
+ return (WhiteBalance_t) m_whiteBalanceParam->GetValue();
+}
+
+/**
+ * Write the color level to the camera.
+ * @param colorLevel valid values are 0 .. 100
+ */
+void AxisCameraParams::WriteColorLevel(int colorLevel)
+{
+ m_colorLevelParam->SetValue(colorLevel);
+ semGive(m_paramChangedSem);
+}
+
+/**
+ * Retrieve the color level from the camera.
+ * @Returns the camera color level.
+ */
+int AxisCameraParams::GetColorLevel()
+{
+ return m_colorLevelParam->GetValue();
+}
+
+/**
+ * Write the exposure control value to the camera.
+ * @param exposureControl A mode to write in the Exposure_t enum.
+ */
+void AxisCameraParams::WriteExposureControl(Exposure_t exposureControl)
+{
+ m_exposureControlParam->SetValue(exposureControl);
+ semGive(m_paramChangedSem);
+}
+
+/**
+ * Get the exposure value from the camera.
+ * @returns the exposure value from the camera.
+ */
+AxisCameraParams::Exposure_t AxisCameraParams::GetExposureControl()
+{
+ return (Exposure_t) m_exposureControlParam->GetValue();
+}
+
+/**
+ * Write resolution value to camera.
+ * @param resolution The camera resolution value to write to the camera. Use the Resolution_t enum.
+ */
+void AxisCameraParams::WriteResolution(Resolution_t resolution)
+{
+ m_resolutionParam->SetValue(resolution);
+ semGive(m_paramChangedSem);
+}
+
+/**
+ * Get the resolution value from the camera.
+ * @returns resultion value for the camera.
+ */
+AxisCameraParams::Resolution_t AxisCameraParams::GetResolution()
+{
+ return (Resolution_t) m_resolutionParam->GetValue();
+}
+
+/**
+ * Write the exposre priority value to the camera.
+ * @param exposurePriority Valid values are 0, 50, 100.
+ * 0 = Prioritize image quality
+ * 50 = None
+ * 100 = Prioritize frame rate
+ */
+void AxisCameraParams::WriteExposurePriority(int exposurePriority)
+{
+ m_exposurePriorityParam->SetValue(exposurePriority);
+ semGive(m_paramChangedSem);
+}
+
+int AxisCameraParams::GetExposurePriority()
+{
+ return m_exposurePriorityParam->GetValue();
+}
+
+/**
+ * Write the rotation value to the camera.
+ * If you mount your camera upside down, use this to adjust the image for you.
+ * @param rotation The image from the Rotation_t enum in AxisCameraParams (kRotation_0 or kRotation_180)
+ */
+void AxisCameraParams::WriteRotation(Rotation_t rotation)
+{
+ m_rotationParam->SetValue(rotation);
+ semGive(m_paramChangedSem);
+}
+
+/**
+ * Get the rotation value from the camera.
+ * @return The rotation value from the camera (Rotation_t).
+ */
+AxisCameraParams::Rotation_t AxisCameraParams::GetRotation()
+{
+ return (Rotation_t) m_rotationParam->GetValue();
+}
+
+/**
+ * Write the compression value to the camera.
+ * @param compression Values between 0 and 100.
+ */
+
+void AxisCameraParams::WriteCompression(int compression)
+{
+ m_compressionParam->SetValue(compression);
+ semGive(m_paramChangedSem);
+}
+
+/**
+ * Get the compression value from the camera.
+ * @return The cached compression value from the camera.
+ */
+int AxisCameraParams::GetCompression()
+{
+ return m_compressionParam->GetValue();
+}
+
+/**
+ * Write the maximum frames per second that the camera should send
+ * Write 0 to send as many as possible.
+ * @param maxFPS The number of frames the camera should send in a second, exposure permitting.
+ */
+void AxisCameraParams::WriteMaxFPS(int maxFPS)
+{
+ m_maxFPSParam->SetValue(maxFPS);
+ semGive(m_paramChangedSem);
+}
+
+/**
+ * Get the max number of frames per second that the camera will send
+ * @return Maximum frames per second.
+ */
+int AxisCameraParams::GetMaxFPS()
+{
+ return m_maxFPSParam->GetValue();
+}
+
+/**
+ * Update a camera parameter.
+ * Write a camera parameter to the camera when it has bene changed.
+ * @param param the string to insert into the http request.
+ * @returns 0 if it failed, otherwise nonzero.
+ */
+int AxisCameraParams::UpdateCamParam(const char* param)
+{
+ char *requestString =
+ "GET /axis-cgi/admin/param.cgi?action=update&%s HTTP/1.1\n\
+User-Agent: HTTPStreamClient\n\
+Connection: Keep-Alive\n\
+Cache-Control: no-cache\n\
+Authorization: Basic RlJDOkZSQw==\n\n";
+ char completedRequest[1024];
+ sprintf(completedRequest, requestString, param);
+ // Send request
+ int camSocket = CreateCameraSocket(completedRequest);
+ if (camSocket == ERROR)
+ {
+ printf("UpdateCamParam failed: %s\n", param);
+ return 0;
+ }
+ close(camSocket);
+ return 1;
+}
+
+/**
+ * Read the full param list from camera, use regular expressions to find the bits we care about
+ * assign values to member variables.
+ */
+int AxisCameraParams::ReadCamParams()
+{
+ char * requestString =
+ "GET /axis-cgi/admin/param.cgi?action=list HTTP/1.1\n\
+User-Agent: HTTPStreamClient\n\
+Connection: Keep-Alive\n\
+Cache-Control: no-cache\n\
+Authorization: Basic RlJDOkZSQw==\n\n";
+
+ int camSocket = CreateCameraSocket(requestString);
+ if (camSocket == ERROR)
+ {
+ return 0;
+ }
+ // Allocate on the heap since it is very large and only needed once
+ char *readBuffer = new char[27000];
+ int totalRead = 0;
+ while (1)
+ {
+ wpi_assert(totalRead < 26000);
+ int bytesRead = recv(camSocket, &readBuffer[totalRead], 1000, 0);
+ if (bytesRead == ERROR)
+ {
+ wpi_setErrnoErrorWithContext("Failed to read image header");
+ close(camSocket);
+ return 0;
+ }
+ else if (bytesRead <= 0)
+ {
+ break;
+ }
+ totalRead += bytesRead;
+ }
+ readBuffer[totalRead] = '\0';
+
+ ParameterVector_t::iterator it = m_parameters.begin();
+ ParameterVector_t::iterator end = m_parameters.end();
+ for(; it != end; it++)
+ {
+ (*it)->GetParamFromString(readBuffer, totalRead);
+ }
+ close(camSocket);
+ delete [] readBuffer;
+ return 1;
+}
+
+/*
+ * Create a socket connected to camera
+ * Used to create a connection to the camera by both AxisCameraParams and AxisCamera.
+ * @param requestString The initial request string to send upon successful connection.
+ * @return ERROR if failed, socket handle if successful.
+ */
+int AxisCameraParams::CreateCameraSocket(const char *requestString)
+{
+ int sockAddrSize;
+ struct sockaddr_in serverAddr;
+ int camSocket;
+ /* create socket */
+ if ((camSocket = socket(AF_INET, SOCK_STREAM, 0)) == ERROR)
+ {
+ wpi_setErrnoErrorWithContext("Failed to create the camera socket");
+ return ERROR;
+ }
+
+ sockAddrSize = sizeof(struct sockaddr_in);
+ bzero((char *) &serverAddr, sockAddrSize);
+ serverAddr.sin_family = AF_INET;
+ serverAddr.sin_len = (u_char) sockAddrSize;
+ serverAddr.sin_port = htons(80);
+
+ serverAddr.sin_addr.s_addr = m_ipAddress;
+
+ /* connect to server */
+ struct timeval connectTimeout;
+ connectTimeout.tv_sec = 5;
+ connectTimeout.tv_usec = 0;
+ if (connectWithTimeout(camSocket, (struct sockaddr *) &serverAddr, sockAddrSize, &connectTimeout) == ERROR)
+ {
+ wpi_setErrnoErrorWithContext("Failed to connect to the camera");
+ close(camSocket);
+ return ERROR;
+ }
+ int sent = send(camSocket, requestString, strlen(requestString), 0);
+ if (sent == ERROR)
+ {
+ wpi_setErrnoErrorWithContext("Failed to send a request to the camera");
+ close(camSocket);
+ return ERROR;
+ }
+ return camSocket;
+}
diff --git a/aos/externals/WPILib/WPILib/Vision/AxisCameraParams.h b/aos/externals/WPILib/WPILib/Vision/AxisCameraParams.h
new file mode 100644
index 0000000..a98b007
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/AxisCameraParams.h
@@ -0,0 +1,90 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __AXIS_CAMERA_PARAMS_H__
+#define __AXIS_CAMERA_PARAMS_H__
+
+#include "EnumCameraParameter.h"
+#include "ErrorBase.h"
+#include "IntCameraParameter.h"
+#include "Task.h"
+#include <vector>
+
+/**
+ * AxisCameraParams class.
+ * This class handles parameter configuration the Axis 206 Ethernet Camera.
+ * It starts up a tasks with an independent connection to the camera that monitors
+ * for changes to parameters and updates the camera.
+ * It is only separate from AxisCamera to isolate the parameter code from the image streaming code.
+ */
+class AxisCameraParams : public ErrorBase
+{
+public:
+ typedef enum Exposure_t {kExposure_Automatic, kExposure_Hold, kExposure_FlickerFree50Hz, kExposure_FlickerFree60Hz};
+ typedef enum WhiteBalance_t {kWhiteBalance_Automatic, kWhiteBalance_Hold, kWhiteBalance_FixedOutdoor1, kWhiteBalance_FixedOutdoor2, kWhiteBalance_FixedIndoor, kWhiteBalance_FixedFlourescent1, kWhiteBalance_FixedFlourescent2};
+ typedef enum Resolution_t {kResolution_640x480, kResolution_640x360, kResolution_320x240, kResolution_160x120};
+ typedef enum Rotation_t {kRotation_0, kRotation_180};
+
+protected:
+ AxisCameraParams(const char* ipAddress);
+ virtual ~AxisCameraParams();
+
+public:
+ // Mid-stream gets & writes
+ void WriteBrightness(int);
+ int GetBrightness();
+ void WriteWhiteBalance(WhiteBalance_t whiteBalance);
+ WhiteBalance_t GetWhiteBalance();
+ void WriteColorLevel(int);
+ int GetColorLevel();
+ void WriteExposureControl(Exposure_t);
+ Exposure_t GetExposureControl();
+ void WriteExposurePriority(int);
+ int GetExposurePriority();
+ void WriteMaxFPS(int);
+ int GetMaxFPS();
+
+ // New-Stream gets & writes (i.e. require restart)
+ void WriteResolution(Resolution_t);
+ Resolution_t GetResolution();
+ void WriteCompression(int);
+ int GetCompression();
+ void WriteRotation(Rotation_t);
+ Rotation_t GetRotation();
+
+protected:
+ virtual void RestartCameraTask() = 0;
+ int CreateCameraSocket(const char *requestString);
+
+ static int s_ParamTaskFunction(AxisCameraParams* thisPtr);
+ int ParamTaskFunction();
+
+ int UpdateCamParam(const char *param);
+ int ReadCamParams();
+
+ Task m_paramTask;
+ UINT32 m_ipAddress; // IPv4
+ SEM_ID m_paramChangedSem;
+ SEM_ID m_socketPossessionSem;
+
+ //Camera Properties
+ IntCameraParameter *m_brightnessParam;
+ IntCameraParameter *m_compressionParam;
+ IntCameraParameter *m_exposurePriorityParam;
+ IntCameraParameter *m_colorLevelParam;
+ IntCameraParameter *m_maxFPSParam;
+ EnumCameraParameter *m_rotationParam;
+ EnumCameraParameter *m_resolutionParam;
+ EnumCameraParameter *m_exposureControlParam;
+ EnumCameraParameter *m_whiteBalanceParam;
+
+ // A vector to access all properties simply.
+ typedef std::vector<IntCameraParameter*> ParameterVector_t;
+ ParameterVector_t m_parameters;
+};
+
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Vision/BinaryImage.cpp b/aos/externals/WPILib/WPILib/Vision/BinaryImage.cpp
new file mode 100644
index 0000000..55c8802
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/BinaryImage.cpp
@@ -0,0 +1,222 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "BinaryImage.h"
+#include "WPIErrors.h"
+
+/** Private NI function needed to write to the VxWorks target */
+IMAQ_FUNC int Priv_SetWriteFileAllowed(UINT32 enable);
+
+BinaryImage::BinaryImage() : MonoImage()
+{
+}
+
+BinaryImage::~BinaryImage()
+{
+}
+
+/**
+ * Get then number of particles for the image.
+ * @returns the number of particles found for the image.
+ */
+int BinaryImage::GetNumberParticles()
+{
+ int numParticles = 0;
+ int success = imaqCountParticles(m_imaqImage, 1, &numParticles);
+ wpi_setImaqErrorWithContext(success, "Error counting particles");
+ return numParticles;
+}
+
+/**
+ * Get a single particle analysis report.
+ * Get one (of possibly many) particle analysis reports for an image.
+ * @param particleNumber Which particle analysis report to return.
+ * @returns the selected particle analysis report
+ */
+ParticleAnalysisReport BinaryImage::GetParticleAnalysisReport(int particleNumber)
+{
+ ParticleAnalysisReport par;
+ GetParticleAnalysisReport(particleNumber, &par);
+ return par;
+}
+
+/**
+ * Get a single particle analysis report.
+ * Get one (of possibly many) particle analysis reports for an image.
+ * This version could be more efficient when copying many reports.
+ * @param particleNumber Which particle analysis report to return.
+ * @param par the selected particle analysis report
+ */
+void BinaryImage::GetParticleAnalysisReport(int particleNumber, ParticleAnalysisReport *par)
+{
+ int success;
+ int numParticles = 0;
+
+ success = imaqGetImageSize(m_imaqImage, &par->imageWidth, &par->imageHeight);
+ wpi_setImaqErrorWithContext(success, "Error getting image size");
+ if (StatusIsFatal())
+ return;
+
+ success = imaqCountParticles(m_imaqImage, 1, &numParticles);
+ wpi_setImaqErrorWithContext(success, "Error counting particles");
+ if (StatusIsFatal())
+ return;
+
+ if (particleNumber >= numParticles)
+ {
+ wpi_setWPIErrorWithContext(ParameterOutOfRange, "particleNumber");
+ return;
+ }
+
+ par->particleIndex = particleNumber;
+ // Don't bother measuring the rest of the particle if one fails
+ bool good = ParticleMeasurement(particleNumber, IMAQ_MT_CENTER_OF_MASS_X, &par->center_mass_x);
+ good = good && ParticleMeasurement(particleNumber, IMAQ_MT_CENTER_OF_MASS_Y, &par->center_mass_y);
+ good = good && ParticleMeasurement(particleNumber, IMAQ_MT_AREA, &par->particleArea);
+ good = good && ParticleMeasurement(particleNumber, IMAQ_MT_BOUNDING_RECT_TOP, &par->boundingRect.top);
+ good = good && ParticleMeasurement(particleNumber, IMAQ_MT_BOUNDING_RECT_LEFT, &par->boundingRect.left);
+ good = good && ParticleMeasurement(particleNumber, IMAQ_MT_BOUNDING_RECT_HEIGHT, &par->boundingRect.height);
+ good = good && ParticleMeasurement(particleNumber, IMAQ_MT_BOUNDING_RECT_WIDTH, &par->boundingRect.width);
+ good = good && ParticleMeasurement(particleNumber, IMAQ_MT_AREA_BY_IMAGE_AREA, &par->particleToImagePercent);
+ good = good && ParticleMeasurement(particleNumber, IMAQ_MT_AREA_BY_PARTICLE_AND_HOLES_AREA, &par->particleQuality);
+
+ if (good)
+ {
+ /* normalized position (-1 to 1) */
+ par->center_mass_x_normalized = NormalizeFromRange(par->center_mass_x, par->imageWidth);
+ par->center_mass_y_normalized = NormalizeFromRange(par->center_mass_y, par->imageHeight);
+ }
+}
+
+
+/**
+ * Get an ordered vector of particles for the image.
+ * Create a vector of particle analysis reports sorted by size for an image.
+ * The vector contains the actual report structures.
+ * @returns a pointer to the vector of particle analysis reports. The caller must delete the
+ * vector when finished using it.
+ */
+vector<ParticleAnalysisReport>* BinaryImage::GetOrderedParticleAnalysisReports()
+{
+ vector<ParticleAnalysisReport>* particles = new vector<ParticleAnalysisReport>;
+ int particleCount = GetNumberParticles();
+ for(int particleIndex = 0; particleIndex < particleCount; particleIndex++)
+ {
+ particles->push_back(GetParticleAnalysisReport(particleIndex));
+ }
+ // TODO: This is pretty inefficient since each compare in the sort copies
+ // both reports being compared... do it manually instead... while we're
+ // at it, we should provide a version that allows a preallocated buffer of
+ // ParticleAnalysisReport structures
+ sort(particles->begin(), particles->end(), CompareParticleSizes);
+ return particles;
+}
+
+/**
+ * Write a binary image to flash.
+ * Writes the binary image to flash on the cRIO for later inspection.
+ * @param fileName the name of the image file written to the flash.
+ */
+void BinaryImage::Write(const char *fileName)
+{
+ RGBValue colorTable[256];
+ Priv_SetWriteFileAllowed(1);
+ memset(colorTable, 0, sizeof(colorTable));
+ colorTable[0].R = 0;
+ colorTable[1].R = 255;
+ colorTable[0].G = colorTable[1].G = 0;
+ colorTable[0].B = colorTable[1].B = 0;
+ colorTable[0].alpha = colorTable[1].alpha = 0;
+ imaqWriteFile(m_imaqImage, fileName, colorTable);
+}
+
+/**
+ * Measure a single parameter for an image.
+ * Get the measurement for a single parameter about an image by calling the imaqMeasureParticle
+ * function for the selected parameter.
+ * @param particleNumber which particle in the set of particles
+ * @param whatToMeasure the imaq MeasurementType (what to measure)
+ * @param result the value of the measurement
+ * @returns false on failure, true on success
+ */
+bool BinaryImage::ParticleMeasurement(int particleNumber, MeasurementType whatToMeasure, int *result)
+{
+ double resultDouble;
+ bool success = ParticleMeasurement(particleNumber, whatToMeasure, &resultDouble);
+ *result = (int)resultDouble;
+ return success;
+}
+
+/**
+ * Measure a single parameter for an image.
+ * Get the measurement for a single parameter about an image by calling the imaqMeasureParticle
+ * function for the selected parameter.
+ * @param particleNumber which particle in the set of particles
+ * @param whatToMeasure the imaq MeasurementType (what to measure)
+ * @param result the value of the measurement
+ * @returns true on failure, false on success
+ */
+bool BinaryImage::ParticleMeasurement(int particleNumber, MeasurementType whatToMeasure, double *result)
+{
+ int success;
+ success = imaqMeasureParticle(m_imaqImage, particleNumber, 0, whatToMeasure, result);
+ wpi_setImaqErrorWithContext(success, "Error measuring particle");
+ return !StatusIsFatal();
+}
+
+//Normalizes to [-1,1]
+double BinaryImage::NormalizeFromRange(double position, int range)
+{
+ return (position * 2.0 / (double)range) - 1.0;
+}
+
+/**
+ * The compare helper function for sort.
+ * This function compares two particle analysis reports as a helper for the sort function.
+ * @param particle1 The first particle to compare
+ * @param particle2 the second particle to compare
+ * @returns true if particle1 is greater than particle2
+ */
+bool BinaryImage::CompareParticleSizes(ParticleAnalysisReport particle1, ParticleAnalysisReport particle2)
+{
+ //we want descending sort order
+ return particle1.particleToImagePercent > particle2.particleToImagePercent;
+}
+
+BinaryImage *BinaryImage::RemoveSmallObjects(bool connectivity8, int erosions)
+{
+ BinaryImage *result = new BinaryImage();
+ int success = imaqSizeFilter(result->GetImaqImage(), m_imaqImage, connectivity8, erosions, IMAQ_KEEP_LARGE, NULL);
+ wpi_setImaqErrorWithContext(success, "Error in RemoveSmallObjects");
+ return result;
+}
+
+BinaryImage *BinaryImage::RemoveLargeObjects(bool connectivity8, int erosions)
+{
+ BinaryImage *result = new BinaryImage();
+ int success = imaqSizeFilter(result->GetImaqImage(), m_imaqImage, connectivity8, erosions, IMAQ_KEEP_SMALL, NULL);
+ wpi_setImaqErrorWithContext(success, "Error in RemoveLargeObjects");
+ return result;
+}
+
+BinaryImage *BinaryImage::ConvexHull(bool connectivity8)
+{
+ BinaryImage *result = new BinaryImage();
+ int success = imaqConvexHull(result->GetImaqImage(), m_imaqImage, connectivity8);
+ wpi_setImaqErrorWithContext(success, "Error in convex hull operation");
+ return result;
+}
+
+BinaryImage *BinaryImage::ParticleFilter(ParticleFilterCriteria2 *criteria, int criteriaCount)
+{
+ BinaryImage *result = new BinaryImage();
+ int numParticles;
+ ParticleFilterOptions2 filterOptions = {0, 0, 0, 1};
+ int success = imaqParticleFilter4(result->GetImaqImage(), m_imaqImage, criteria, criteriaCount, &filterOptions, NULL, &numParticles);
+ wpi_setImaqErrorWithContext(success, "Error in particle filter operation");
+ return result;
+}
+
diff --git a/aos/externals/WPILib/WPILib/Vision/BinaryImage.h b/aos/externals/WPILib/WPILib/Vision/BinaryImage.h
new file mode 100644
index 0000000..23a8557
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/BinaryImage.h
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __BINARY_IMAGE_H__
+#define __BINARY_IMAGE_H__
+
+#include "MonoImage.h"
+/**
+ * Included for ParticleAnalysisReport definition
+ * TODO: Eliminate this dependency!
+ */
+#include "Vision2009/VisionAPI.h"
+
+#include <vector>
+#include <algorithm>
+using namespace std;
+
+class BinaryImage : public MonoImage
+{
+public:
+ BinaryImage();
+ virtual ~BinaryImage();
+ int GetNumberParticles();
+ ParticleAnalysisReport GetParticleAnalysisReport(int particleNumber);
+ void GetParticleAnalysisReport(int particleNumber, ParticleAnalysisReport *par);
+ vector<ParticleAnalysisReport>* GetOrderedParticleAnalysisReports();
+ BinaryImage *RemoveSmallObjects(bool connectivity8, int erosions);
+ BinaryImage *RemoveLargeObjects(bool connectivity8, int erosions);
+ BinaryImage *ConvexHull(bool connectivity8);
+ BinaryImage *ParticleFilter(ParticleFilterCriteria2 *criteria, int criteriaCount);
+ virtual void Write(const char *fileName);
+private:
+ bool ParticleMeasurement(int particleNumber, MeasurementType whatToMeasure, int *result);
+ bool ParticleMeasurement(int particleNumber, MeasurementType whatToMeasure, double *result);
+ static double NormalizeFromRange(double position, int range);
+ static bool CompareParticleSizes(ParticleAnalysisReport particle1, ParticleAnalysisReport particle2);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Vision/ColorImage.cpp b/aos/externals/WPILib/WPILib/Vision/ColorImage.cpp
new file mode 100644
index 0000000..24c44f4
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/ColorImage.cpp
@@ -0,0 +1,465 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "ColorImage.h"
+
+#include "WPIErrors.h"
+
+ColorImage::ColorImage(ImageType type) : ImageBase(type)
+{
+}
+
+ColorImage::~ColorImage()
+{
+}
+
+/**
+ * Perform a threshold operation on a ColorImage.
+ * Perform a threshold operation on a ColorImage using the ColorMode supplied
+ * as a parameter.
+ * @param colorMode The type of colorspace this operation should be performed in
+ * @returns a pointer to a binary image
+ */
+BinaryImage *ColorImage::ComputeThreshold(ColorMode colorMode,
+ int low1, int high1,
+ int low2, int high2,
+ int low3, int high3)
+{
+ BinaryImage *result = new BinaryImage();
+ Range range1 = {low1, high1},
+ range2 = {low2, high2},
+ range3 = {low3, high3};
+
+ int success = imaqColorThreshold(result->GetImaqImage(), m_imaqImage, 1, colorMode, &range1, &range2, &range3);
+ wpi_setImaqErrorWithContext(success, "ImaqThreshold error");
+ return result;
+}
+
+/**
+ * Perform a threshold in RGB space.
+ * @param redLow Red low value
+ * @param redHigh Red high value
+ * @param greenLow Green low value
+ * @param greenHigh Green high value
+ * @param blueLow Blue low value
+ * @param blueHigh Blue high value
+ * @returns A pointer to a BinaryImage that represents the result of the threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdRGB(int redLow, int redHigh, int greenLow, int greenHigh, int blueLow, int blueHigh)
+{
+ return ComputeThreshold(IMAQ_RGB, redLow, redHigh, greenLow, greenHigh, blueLow, blueHigh);
+}
+
+/**
+ * Perform a threshold in RGB space.
+ * @param threshold a reference to the Threshold object to use.
+ * @returns A pointer to a BinaryImage that represents the result of the threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdRGB(Threshold &t)
+{
+ return ComputeThreshold(IMAQ_RGB, t.plane1Low, t.plane1High,
+ t.plane2Low, t.plane2High,
+ t.plane3Low, t.plane3High);
+}
+
+/**
+ * Perform a threshold in HSL space.
+ * @param hueLow Low value for hue
+ * @param hueHigh High value for hue
+ * @param saturationLow Low value for saturation
+ * @param saturationHigh High value for saturation
+ * @param luminenceLow Low value for luminence
+ * @param luminenceHigh High value for luminence
+ * @returns a pointer to a BinaryImage that represents the result of the threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSL(int hueLow, int hueHigh, int saturationLow, int saturationHigh, int luminenceLow, int luminenceHigh)
+{
+ return ComputeThreshold(IMAQ_HSL, hueLow, hueHigh, saturationLow, saturationHigh, luminenceLow, luminenceHigh);
+}
+
+/**
+ * Perform a threshold in HSL space.
+ * @param threshold a reference to the Threshold object to use.
+ * @returns A pointer to a BinaryImage that represents the result of the threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSL(Threshold &t)
+{
+ return ComputeThreshold(IMAQ_HSL, t.plane1Low, t.plane1High,
+ t.plane2Low, t.plane2High,
+ t.plane3Low, t.plane3High);
+}
+
+/**
+ * Perform a threshold in HSV space.
+ * @param hueLow Low value for hue
+ * @param hueHigh High value for hue
+ * @param saturationLow Low value for saturation
+ * @param saturationHigh High value for saturation
+ * @param valueLow Low value
+ * @param valueHigh High value
+ * @returns a pointer to a BinaryImage that represents the result of the threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSV(int hueLow, int hueHigh, int saturationLow, int saturationHigh, int valueLow, int valueHigh)
+{
+ return ComputeThreshold(IMAQ_HSV, hueLow, hueHigh, saturationLow, saturationHigh, valueLow, valueHigh);
+}
+
+/**
+ * Perform a threshold in HSV space.
+ * @param threshold a reference to the Threshold object to use.
+ * @returns A pointer to a BinaryImage that represents the result of the threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSV(Threshold &t)
+{
+ return ComputeThreshold(IMAQ_HSV, t.plane1Low, t.plane1High,
+ t.plane2Low, t.plane2High,
+ t.plane3Low, t.plane3High);
+}
+
+/**
+ * Perform a threshold in HSI space.
+ * @param hueLow Low value for hue
+ * @param hueHigh High value for hue
+ * @param saturationLow Low value for saturation
+ * @param saturationHigh High value for saturation
+ * @param valueLow Low intensity
+ * @param valueHigh High intensity
+ * @returns a pointer to a BinaryImage that represents the result of the threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSI(int hueLow, int hueHigh, int saturationLow, int saturationHigh, int intensityLow, int intensityHigh)
+{
+ return ComputeThreshold(IMAQ_HSI, hueLow, hueHigh, saturationLow, saturationHigh, intensityLow, intensityHigh);
+}
+
+/**
+ * Perform a threshold in HSI space.
+ * @param threshold a reference to the Threshold object to use.
+ * @returns A pointer to a BinaryImage that represents the result of the threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSI(Threshold &t)
+{
+ return ComputeThreshold(IMAQ_HSI, t.plane1Low, t.plane1High,
+ t.plane2Low, t.plane2High,
+ t.plane3Low, t.plane3High);
+}
+
+/**
+ * Extract a color plane from the image
+ * @param mode The ColorMode to use for the plane extraction
+ * @param planeNumber Which plane is to be extracted
+ * @returns A pointer to a MonoImage that represents the extracted plane.
+ */
+MonoImage *ColorImage::ExtractColorPlane(ColorMode mode, int planeNumber)
+{
+ MonoImage *result = new MonoImage();
+ if (m_imaqImage == NULL)
+ wpi_setWPIError(NullParameter);
+ int success = imaqExtractColorPlanes(m_imaqImage,
+ mode,
+ (planeNumber == 1) ? result->GetImaqImage() : NULL,
+ (planeNumber == 2) ? result->GetImaqImage() : NULL,
+ (planeNumber == 3) ? result->GetImaqImage() : NULL);
+ wpi_setImaqErrorWithContext(success, "Imaq ExtractColorPlanes failed");
+ return result;
+}
+
+/*
+ * Extract the first color plane for an image.
+ * @param mode The color mode in which to operate
+ * @returns a pointer to a MonoImage that is the extracted plane.
+ */
+MonoImage *ColorImage::ExtractFirstColorPlane(ColorMode mode)
+{
+ return ExtractColorPlane(mode, 1);
+}
+
+/*
+ * Extract the second color plane for an image.
+ * @param mode The color mode in which to operate
+ * @returns a pointer to a MonoImage that is the extracted plane.
+ */
+MonoImage *ColorImage::ExtractSecondColorPlane(ColorMode mode)
+{
+ return ExtractColorPlane(mode, 2);
+}
+
+/*
+ * Extract the third color plane for an image.
+ * @param mode The color mode in which to operate
+ * @returns a pointer to a MonoImage that is the extracted plane.
+ */
+MonoImage *ColorImage::ExtractThirdColorPlane(ColorMode mode)
+{
+ return ExtractColorPlane(mode, 3);
+}
+
+/*
+ * Extract the red plane from an RGB image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetRedPlane()
+{
+ return ExtractFirstColorPlane(IMAQ_RGB);
+}
+
+/*
+ * Extract the green plane from an RGB image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetGreenPlane()
+{
+ return ExtractSecondColorPlane(IMAQ_RGB);
+}
+
+/*
+ * Extract the blue plane from an RGB image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetBluePlane()
+{
+ return ExtractThirdColorPlane(IMAQ_RGB);
+}
+
+/*
+ * Extract the Hue plane from an HSL image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetHSLHuePlane()
+{
+ return ExtractFirstColorPlane(IMAQ_HSL);
+}
+
+/*
+ * Extract the Hue plane from an HSV image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetHSVHuePlane()
+{
+ return ExtractFirstColorPlane(IMAQ_HSV);
+}
+
+/*
+ * Extract the Hue plane from an HSI image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetHSIHuePlane()
+{
+ return ExtractFirstColorPlane(IMAQ_HSI);
+}
+
+/*
+ * Extract the Luminance plane from an HSL image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetLuminancePlane()
+{
+ return ExtractThirdColorPlane(IMAQ_HSL);
+}
+
+/*
+ * Extract the Value plane from an HSV image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetValuePlane()
+{
+ return ExtractThirdColorPlane(IMAQ_HSV);
+}
+
+/*
+ * Extract the Intensity plane from an HSI image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetIntensityPlane()
+{
+ return ExtractThirdColorPlane(IMAQ_HSI);
+}
+
+/**
+ * Replace a plane in the ColorImage with a MonoImage
+ * Replaces a single plane in the image with a MonoImage
+ * @param mode The ColorMode in which to operate
+ * @param plane The pointer to the replacement plane as a MonoImage
+ * @param planeNumber The plane number (1, 2, 3) to replace
+ */
+void ColorImage::ReplacePlane(ColorMode mode, MonoImage *plane, int planeNumber) {
+ int success = imaqReplaceColorPlanes(m_imaqImage,
+ (const Image*) m_imaqImage,
+ mode,
+ (planeNumber == 1) ? plane->GetImaqImage() : NULL,
+ (planeNumber == 2) ? plane->GetImaqImage() : NULL,
+ (planeNumber == 3) ? plane->GetImaqImage() : NULL);
+ wpi_setImaqErrorWithContext(success, "Imaq ReplaceColorPlanes failed");
+}
+
+/**
+ * Replace the first color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceFirstColorPlane(ColorMode mode, MonoImage *plane)
+{
+ ReplacePlane(mode, plane, 1);
+}
+
+/**
+ * Replace the second color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceSecondColorPlane(ColorMode mode, MonoImage *plane)
+{
+ ReplacePlane(mode, plane, 2);
+}
+
+/**
+ * Replace the third color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceThirdColorPlane(ColorMode mode, MonoImage *plane)
+{
+ ReplacePlane(mode, plane, 3);
+}
+
+/**
+ * Replace the red color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceRedPlane(MonoImage *plane)
+{
+ ReplaceFirstColorPlane(IMAQ_RGB, plane);
+}
+
+/**
+ * Replace the green color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceGreenPlane(MonoImage *plane)
+{
+ ReplaceSecondColorPlane(IMAQ_RGB, plane);
+}
+
+/**
+ * Replace the blue color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceBluePlane(MonoImage *plane)
+{
+ ReplaceThirdColorPlane(IMAQ_RGB, plane);
+}
+
+
+/**
+ * Replace the Hue color plane in a HSL image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceHSLHuePlane(MonoImage *plane)
+{
+ return ReplaceFirstColorPlane(IMAQ_HSL, plane);
+}
+
+/**
+ * Replace the Hue color plane in a HSV image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceHSVHuePlane(MonoImage *plane)
+{
+ return ReplaceFirstColorPlane(IMAQ_HSV, plane);
+}
+
+/**
+ * Replace the first Hue plane in a HSI image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceHSIHuePlane(MonoImage *plane)
+{
+ return ReplaceFirstColorPlane(IMAQ_HSI, plane);
+}
+
+/**
+ * Replace the Saturation color plane in an HSL image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceHSLSaturationPlane(MonoImage *plane)
+{
+ return ReplaceSecondColorPlane(IMAQ_HSL, plane);
+}
+
+/**
+ * Replace the Saturation color plane in a HSV image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceHSVSaturationPlane(MonoImage *plane)
+{
+ return ReplaceSecondColorPlane(IMAQ_HSV, plane);
+}
+
+/**
+ * Replace the Saturation color plane in a HSI image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceHSISaturationPlane(MonoImage *plane)
+{
+ return ReplaceSecondColorPlane(IMAQ_HSI, plane);
+}
+
+/**
+ * Replace the Luminance color plane in an HSL image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceLuminancePlane(MonoImage *plane)
+{
+ return ReplaceThirdColorPlane(IMAQ_HSL, plane);
+}
+
+/**
+ * Replace the Value color plane in an HSV with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceValuePlane(MonoImage *plane)
+{
+ return ReplaceThirdColorPlane(IMAQ_HSV, plane);
+}
+
+/**
+ * Replace the Intensity color plane in a HSI image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color plane.
+ */
+void ColorImage::ReplaceIntensityPlane(MonoImage *plane)
+{
+ return ReplaceThirdColorPlane(IMAQ_HSI, plane);
+}
+
+//TODO: frcColorEqualize(Image* dest, const Image* source, int colorEqualization) needs to be modified
+//The colorEqualization parameter is discarded and is set to TRUE in the call to imaqColorEqualize.
+void ColorImage::Equalize(bool allPlanes)
+{
+ // Note that this call uses NI-defined TRUE and FALSE
+ int success = imaqColorEqualize(m_imaqImage, (const Image*) m_imaqImage, (allPlanes) ? TRUE : FALSE);
+ wpi_setImaqErrorWithContext(success, "Imaq ColorEqualize error");
+}
+
+void ColorImage::ColorEqualize()
+{
+ Equalize(true);
+}
+
+void ColorImage::LuminanceEqualize()
+{
+ Equalize(false);
+}
diff --git a/aos/externals/WPILib/WPILib/Vision/ColorImage.h b/aos/externals/WPILib/WPILib/Vision/ColorImage.h
new file mode 100644
index 0000000..af71ce9
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/ColorImage.h
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __COLOR_IMAGE_H__
+#define __COLOR_IMAGE_H__
+
+#include "ImageBase.h"
+#include "BinaryImage.h"
+#include "Threshold.h"
+
+class ColorImage : public ImageBase
+{
+public:
+ ColorImage(ImageType type);
+ virtual ~ColorImage();
+ BinaryImage *ThresholdRGB(int redLow, int redHigh, int greenLow, int greenHigh, int blueLow, int blueHigh);
+ BinaryImage *ThresholdHSL(int hueLow, int hueHigh, int saturationLow, int saturationHigh, int luminenceLow, int luminenceHigh);
+ BinaryImage *ThresholdHSV(int hueLow, int hueHigh, int saturationLow, int saturationHigh, int valueHigh, int valueLow);
+ BinaryImage *ThresholdHSI(int hueLow, int hueHigh, int saturationLow, int saturationHigh, int intensityLow, int intensityHigh);
+ BinaryImage *ThresholdRGB(Threshold &threshold);
+ BinaryImage *ThresholdHSL(Threshold &threshold);
+ BinaryImage *ThresholdHSV(Threshold &threshold);
+ BinaryImage *ThresholdHSI(Threshold &threshold);
+ MonoImage *GetRedPlane();
+ MonoImage *GetGreenPlane();
+ MonoImage *GetBluePlane();
+ MonoImage *GetHSLHuePlane();
+ MonoImage *GetHSVHuePlane();
+ MonoImage *GetHSIHuePlane();
+ MonoImage *GetHSLSaturationPlane();
+ MonoImage *GetHSVSaturationPlane();
+ MonoImage *GetHSISaturationPlane();
+ MonoImage *GetLuminancePlane();
+ MonoImage *GetValuePlane();
+ MonoImage *GetIntensityPlane();
+ void ReplaceRedPlane(MonoImage *plane);
+ void ReplaceGreenPlane(MonoImage *plane);
+ void ReplaceBluePlane(MonoImage *plane);
+ void ReplaceHSLHuePlane(MonoImage *plane);
+ void ReplaceHSVHuePlane(MonoImage *plane);
+ void ReplaceHSIHuePlane(MonoImage *plane);
+ void ReplaceHSLSaturationPlane(MonoImage *plane);
+ void ReplaceHSVSaturationPlane(MonoImage *plane);
+ void ReplaceHSISaturationPlane(MonoImage *plane);
+ void ReplaceLuminancePlane(MonoImage *plane);
+ void ReplaceValuePlane(MonoImage *plane);
+ void ReplaceIntensityPlane(MonoImage *plane);
+ void ColorEqualize();
+ void LuminanceEqualize();
+
+private:
+ BinaryImage *ComputeThreshold(ColorMode colorMode, int low1, int high1, int low2, int high2, int low3, int high3);
+ void Equalize(bool allPlanes);
+ MonoImage * ExtractColorPlane(ColorMode mode, int planeNumber);
+ MonoImage * ExtractFirstColorPlane(ColorMode mode);
+ MonoImage * ExtractSecondColorPlane(ColorMode mode);
+ MonoImage * ExtractThirdColorPlane(ColorMode mode);
+ void ReplacePlane(ColorMode mode, MonoImage *plane, int planeNumber);
+ void ReplaceFirstColorPlane(ColorMode mode, MonoImage *plane);
+ void ReplaceSecondColorPlane(ColorMode mode, MonoImage *plane);
+ void ReplaceThirdColorPlane(ColorMode mode, MonoImage *plane);
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Vision/EnumCameraParameter.cpp b/aos/externals/WPILib/WPILib/Vision/EnumCameraParameter.cpp
new file mode 100644
index 0000000..3801836
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/EnumCameraParameter.cpp
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "EnumCameraParameter.h"
+#include <stdio.h>
+#include <string.h>
+
+/**
+ * Constructor for an enumeration camera parameter.
+ * Enumeration camera parameters have lists of value choices and strings that go
+ * with them. There are also C++ enumerations to go along with them.
+ * @param setString The string for an HTTP request to set the value.
+ * @param getString The string for an HTTP request to get the value.
+ * @param choices An array of strings of the parameter choices set in the http strings.
+ * @param numChoices The number of choices in the enumeration set.
+ */
+EnumCameraParameter::EnumCameraParameter(const char *setString, const char *getString, bool requiresRestart,
+ const char *const*choices, int numChoices)
+ : IntCameraParameter(setString, getString, requiresRestart)
+{
+ m_enumValues = choices;
+ m_numChoices = numChoices;
+}
+
+/*
+ * Check if an enumeration camera parameter has changed.
+ * Check if the parameter has changed and update the camera if it has. This is called
+ * from a loop in the parameter checker task.
+ * @returns true if the camera needs to restart
+ */
+bool EnumCameraParameter::CheckChanged(bool &changed, char *param)
+{
+ changed = m_changed;
+ if (m_changed)
+ {
+ m_changed = false;
+ sprintf(param, m_setString, m_enumValues[m_value]);
+ return m_requiresRestart;
+ }
+ return false;
+}
+
+/**
+ * Extract the parameter value from a string.
+ * Extract the parameter value from the camera status message.
+ * @param string The string returned from the camera.
+ * @param length The length of the string from the camera.
+ */
+void EnumCameraParameter::GetParamFromString(const char *string, int stringLength)
+{
+ char resultString[50];
+ if (SearchForParam(m_getString, string, stringLength, resultString) < 0) return;
+ for (int i = 0; i < m_numChoices; i++)
+ {
+ if (strcmp(resultString, m_enumValues[i]) == 0)
+ {
+ if (!m_changed) // don't change parameter that's been set in code
+ {
+ m_value = i;
+ }
+ }
+ }
+}
+
diff --git a/aos/externals/WPILib/WPILib/Vision/EnumCameraParameter.h b/aos/externals/WPILib/WPILib/Vision/EnumCameraParameter.h
new file mode 100644
index 0000000..543209f
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/EnumCameraParameter.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __ENUM_CAMERA_PARAMETER_H__
+#define __ENUM_CAMERA_PARAMETER_H__
+
+#include "IntCameraParameter.h"
+
+/**
+ * Enumerated camera parameter.
+ * This class represents a camera parameter that takes an enumerated type for a value.
+ */
+class EnumCameraParameter: public IntCameraParameter
+{
+private:
+ const char *const*m_enumValues;
+ int m_numChoices;
+
+public:
+ EnumCameraParameter(const char *setString, const char *getString, bool requiresRestart, const char *const*choices, int numChoices);
+ virtual bool CheckChanged(bool &changed, char *param);
+ virtual void GetParamFromString(const char *string, int stringLength);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Vision/HSLImage.cpp b/aos/externals/WPILib/WPILib/Vision/HSLImage.cpp
new file mode 100644
index 0000000..fec283a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/HSLImage.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "HSLImage.h"
+
+/**
+ * Create a new image that uses the Hue, Saturation, and Luminance planes.
+ */
+HSLImage::HSLImage() : ColorImage(IMAQ_IMAGE_HSL)
+{
+}
+
+/**
+ * Create a new image by loading a file.
+ * @param fileName The path of the file to load.
+ */
+HSLImage::HSLImage(const char *fileName) : ColorImage(IMAQ_IMAGE_HSL)
+{
+ int success = imaqReadFile(m_imaqImage, fileName, NULL, NULL);
+ wpi_setImaqErrorWithContext(success, "Imaq ReadFile error");
+}
+
+HSLImage::~HSLImage()
+{
+}
diff --git a/aos/externals/WPILib/WPILib/Vision/HSLImage.h b/aos/externals/WPILib/WPILib/Vision/HSLImage.h
new file mode 100644
index 0000000..fb365ad
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/HSLImage.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __HSL_IMAGE_H__
+#define __HSL_IMAGE_H__
+
+#include "ColorImage.h"
+
+/**
+ * A color image represented in HSL color space at 3 bytes per pixel.
+ */
+class HSLImage : public ColorImage
+{
+public:
+ HSLImage();
+ HSLImage(const char *fileName);
+ virtual ~HSLImage();
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Vision/ImageBase.cpp b/aos/externals/WPILib/WPILib/Vision/ImageBase.cpp
new file mode 100644
index 0000000..9ec70f3
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/ImageBase.cpp
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "ImageBase.h"
+#include "nivision.h"
+
+/** Private NI function needed to write to the VxWorks target */
+IMAQ_FUNC int Priv_SetWriteFileAllowed(UINT32 enable);
+
+/**
+ * Create a new instance of an ImageBase.
+ * Imagebase is the base of all the other image classes. The constructor
+ * creates any type of image and stores the pointer to it in the class.
+ * @param type The type of image to create
+ */
+ImageBase::ImageBase(ImageType type)
+{
+ m_imaqImage = imaqCreateImage(type, DEFAULT_BORDER_SIZE);
+}
+
+/**
+ * Frees memory associated with an ImageBase.
+ * Destructor frees the imaq image allocated with the class.
+ */
+ImageBase::~ImageBase()
+{
+ if(m_imaqImage)
+ imaqDispose(m_imaqImage);
+}
+
+/**
+ * Writes an image to a file with the given filename.
+ * Write the image to a file in the flash on the cRIO.
+ * @param fileName The name of the file to write
+ */
+void ImageBase::Write(const char *fileName)
+{
+ Priv_SetWriteFileAllowed(1);
+ int success = imaqWriteFile(m_imaqImage, fileName, NULL);
+ wpi_setImaqErrorWithContext(success, "Imaq Image writeFile error");
+}
+
+/**
+ * Gets the height of an image.
+ * @return The height of the image in pixels.
+ */
+int ImageBase::GetHeight()
+{
+ int height;
+ imaqGetImageSize(m_imaqImage, NULL, &height);
+ return height;
+}
+
+/**
+ * Gets the width of an image.
+ * @return The width of the image in pixels.
+ */
+int ImageBase::GetWidth()
+{
+ int width;
+ imaqGetImageSize(m_imaqImage, &width, NULL);
+ return width;
+}
+
+/**
+ * Access the internal IMAQ Image data structure.
+ *
+ * @return A pointer to the internal IMAQ Image data structure.
+ */
+Image *ImageBase::GetImaqImage()
+{
+ return m_imaqImage;
+}
+
diff --git a/aos/externals/WPILib/WPILib/Vision/ImageBase.h b/aos/externals/WPILib/WPILib/Vision/ImageBase.h
new file mode 100644
index 0000000..6a45ec1
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/ImageBase.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __IMAGE_BASE_H__
+#define __IMAGE_BASE_H__
+
+#include <stdio.h>
+#include "nivision.h"
+#include "ErrorBase.h"
+
+#define DEFAULT_BORDER_SIZE 3
+
+class ImageBase : public ErrorBase
+{
+public:
+ ImageBase(ImageType type);
+ virtual ~ImageBase();
+ virtual void Write(const char *fileName);
+ int GetHeight();
+ int GetWidth();
+ Image *GetImaqImage();
+protected:
+ Image *m_imaqImage;
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Vision/IntCameraParameter.cpp b/aos/externals/WPILib/WPILib/Vision/IntCameraParameter.cpp
new file mode 100644
index 0000000..af7ff2c
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/IntCameraParameter.cpp
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "IntCameraParameter.h"
+#include "pcre.h"
+#include <stdio.h>
+#include <string.h>
+
+/**
+ * Constructor for an integer camera parameter.
+ * @param setString The string to set a value in the HTTP request
+ * @param getString The string to retrieve a value in the HTTP request
+ */
+IntCameraParameter::IntCameraParameter(const char *setString, const char *getString, bool requiresRestart)
+{
+ m_changed = false;
+ m_value = 0;
+ m_setString = setString;
+ m_getString = getString;
+ m_requiresRestart = requiresRestart;
+}
+
+/**
+ * Get a value for a camera parameter.
+ * @returns The camera parameter cached valued.
+ */
+int IntCameraParameter::GetValue()
+{
+ return m_value;
+}
+
+/**
+ * Set a value for a camera parameter.
+ * Mark the value for change. The value will be updated in the parameter
+ * change loop.
+ */
+void IntCameraParameter::SetValue(int value)
+{
+ m_value = value;
+ m_changed = true;
+}
+
+/**
+ * Check if a parameter has changed and update.
+ * Check if a parameter has changed and send the update string if it
+ * has changed. This is called from the loop in the parameter task loop.
+ * @returns true if the camera needs to restart
+ */
+bool IntCameraParameter::CheckChanged(bool &changed, char *param)
+{
+ changed = m_changed;
+ if (m_changed)
+ {
+ sprintf(param, m_setString, m_value);
+ m_changed = false;
+ return m_requiresRestart;
+ }
+ return false;
+}
+
+/**
+ * Get a parameter value from the string.
+ * Get a parameter value from the camera status string. If it has been changed
+ * been changed by the program, then don't update it. Program values have
+ * precedence over those written in the camera.
+ */
+void IntCameraParameter::GetParamFromString(const char *string, int stringLength)
+{
+ char resultString[150];
+ if (SearchForParam(m_getString, string, stringLength, resultString) >= 0)
+ {
+ if (!m_changed) m_value = atoi(resultString);
+ }
+}
+
+/**
+ * @param pattern: the regular expression
+ * @param searchString the text to search
+ * @param searchStringLen the length of searchString
+ * @param result buffer to put resulting text into, must be pre-allocated
+ */
+int IntCameraParameter::SearchForParam(const char *pattern, const char *searchString, int searchStringLen, char *result)
+{
+ int vectorLen = 10;
+ int resultVector[vectorLen];
+ const char *error;
+ int erroffset;
+ pcre *compiledPattern = pcre_compile(
+ pattern, //"root.Image.I0.Appearance.Resolution=(.*)",
+ PCRE_CASELESS,
+ &error, // for error message
+ &erroffset, // for error offset
+ NULL); // use default character tables
+ int rc;
+ rc = pcre_exec(compiledPattern,
+ NULL,
+ searchString,
+ searchStringLen,
+ 0,
+ 0,
+ resultVector, //locations of submatches
+ vectorLen); //size of ovector
+ int length = resultVector[3] - resultVector[2];
+ memcpy(result, &searchString[resultVector[2]], length);
+ result[length] = '\0';
+ return rc;
+}
+
diff --git a/aos/externals/WPILib/WPILib/Vision/IntCameraParameter.h b/aos/externals/WPILib/WPILib/Vision/IntCameraParameter.h
new file mode 100644
index 0000000..d3bc5ef
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/IntCameraParameter.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __INT_CAMERA_PARAMETER_H__
+#define __INT_CAMERA_PARAMETER_H__
+
+#include <vxWorks.h>
+
+/**
+ * Integer camera parameter.
+ * This class represents a camera parameter that takes an integer value.
+ */
+class IntCameraParameter
+{
+protected:
+ const char *m_setString;
+ const char *m_getString;
+ bool m_changed;
+ bool m_requiresRestart;
+ int m_value; // parameter value
+
+ int SearchForParam(const char *pattern, const char *searchString, int searchStringLen, char *result);
+
+public:
+ IntCameraParameter(const char *setString, const char *getString, bool requiresRestart);
+ int GetValue();
+ void SetValue(int value);
+ virtual bool CheckChanged(bool &changed, char *param);
+ virtual void GetParamFromString(const char *string, int stringLength);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Vision/MonoImage.cpp b/aos/externals/WPILib/WPILib/Vision/MonoImage.cpp
new file mode 100644
index 0000000..f1e0022
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/MonoImage.cpp
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "MonoImage.h"
+#include "nivision.h"
+
+MonoImage::MonoImage() : ImageBase(IMAQ_IMAGE_U8)
+{
+}
+
+MonoImage::~MonoImage()
+{
+}
+
+/**
+ * Look for ellipses in an image.
+ * Given some input parameters, look for any number of ellipses in an image.
+ * @param ellipseDescriptor Ellipse descriptor
+ * @param curveOptions Curve options
+ * @param shapeDetectionOptions Shape detection options
+ * @param roi Region of Interest
+ * @returns a vector of EllipseMatch structures (0 length vector on no match)
+ */
+vector<EllipseMatch> * MonoImage::DetectEllipses(
+ EllipseDescriptor *ellipseDescriptor, CurveOptions *curveOptions,
+ ShapeDetectionOptions *shapeDetectionOptions, ROI *roi)
+{
+ int numberOfMatches;
+ EllipseMatch *e = imaqDetectEllipses(m_imaqImage, ellipseDescriptor,
+ curveOptions, shapeDetectionOptions, roi, &numberOfMatches);
+ vector<EllipseMatch> *ellipses = new vector<EllipseMatch>;
+ if (e == NULL)
+ {
+ return ellipses;
+ }
+ for (int i = 0; i < numberOfMatches; i++)
+ {
+ ellipses->push_back(e[i]);
+ }
+ imaqDispose(e);
+ return ellipses;
+}
+
+vector<EllipseMatch> * MonoImage::DetectEllipses(
+ EllipseDescriptor *ellipseDescriptor)
+{
+ vector<EllipseMatch> *ellipses = DetectEllipses(ellipseDescriptor, NULL,
+ NULL, NULL);
+ return ellipses;
+}
diff --git a/aos/externals/WPILib/WPILib/Vision/MonoImage.h b/aos/externals/WPILib/WPILib/Vision/MonoImage.h
new file mode 100644
index 0000000..277ff3a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/MonoImage.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __MONO_IMAGE_H__
+#define __MONO_IMAGE_H__
+
+#include "ImageBase.h"
+
+#include <vector>
+
+using namespace std;
+
+class MonoImage : public ImageBase
+{
+public:
+ MonoImage();
+ virtual ~MonoImage();
+
+ vector<EllipseMatch> * DetectEllipses(EllipseDescriptor *ellipseDescriptor,
+ CurveOptions *curveOptions,
+ ShapeDetectionOptions *shapeDetectionOptions,
+ ROI *roi);
+ vector<EllipseMatch> * DetectEllipses(EllipseDescriptor *ellipseDescriptor);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Vision/PCVideoServer.cpp b/aos/externals/WPILib/WPILib/Vision/PCVideoServer.cpp
new file mode 100644
index 0000000..4cae9d0
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/PCVideoServer.cpp
@@ -0,0 +1,281 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include <vxWorks.h>
+
+#include "PCVideoServer.h"
+
+#include <errnoLib.h>
+#include <hostLib.h>
+#include <inetLib.h>
+#include <sockLib.h>
+
+#include "NetworkCommunication/UsageReporting.h"
+#include "Task.h"
+#include "Timer.h"
+#include "Vision/AxisCamera.h"
+#include "WPIErrors.h"
+
+/**
+ * @brief Implements an object that automatically does a close on a
+ * camera socket on destruction.
+ */
+class ScopedSocket {
+public:
+ ScopedSocket(int camSock)
+ : m_camSock(camSock)
+ {
+ }
+
+ ~ScopedSocket() {
+ if (m_camSock != ERROR) {
+ close(m_camSock);
+ }
+ }
+ // Cast to int allows you to pass this to any function that
+ // takes the socket as an int.
+ operator int() const {
+ return m_camSock;
+ }
+
+private:
+ int m_camSock;
+};
+
+//============================================================================
+// PCVideoServer
+//============================================================================
+
+/**
+ * @brief Constructor.
+ */
+PCVideoServer::PCVideoServer()
+ : m_serverTask("PCVideoServer", (FUNCPTR)s_ServerTask)
+ , m_newImageSem (NULL)
+ , m_stopServer (false)
+{
+ AxisCamera &cam = AxisCamera::GetInstance();
+ m_newImageSem = cam.GetNewImageSem();
+ if (!cam.StatusIsFatal())
+ {
+ StartServerTask();
+ }
+ else
+ {
+ CloneError(&cam);
+ }
+}
+
+/**
+ * @brief Destructor.
+ * Stop serving images and destroy this class.
+ */
+PCVideoServer::~PCVideoServer()
+{
+ // Stop the images to PC server.
+ Stop();
+ // Clear the error so that you can use this object to make a connection to
+ // the VIDEO_TO_PC_PORT to stop the ImageToPCServer if it is waiting to
+ // accept connections from a PC.
+ ClearError();
+ // Open a socket.
+ int camSock = socket(AF_INET, SOCK_STREAM, 0);
+ if (camSock == ERROR)
+ {
+ wpi_setErrnoError();
+ return;
+ }
+ ScopedSocket scopedCamSock(camSock);
+ // If successful
+ if (!StatusIsFatal())
+ {
+ // Create a connection to the localhost.
+ struct sockaddr_in selfAddr;
+ int sockAddrSize = sizeof(selfAddr);
+ bzero ((char *) &selfAddr, sockAddrSize);
+ selfAddr.sin_family = AF_INET;
+ selfAddr.sin_len = (u_char) sockAddrSize;
+ selfAddr.sin_port = htons (VIDEO_TO_PC_PORT);
+
+ if (( (int)(selfAddr.sin_addr.s_addr = inet_addr (const_cast<char*>("localhost")) ) != ERROR) ||
+ ( (int)(selfAddr.sin_addr.s_addr = hostGetByName (const_cast<char*>("localhost")) ) != ERROR))
+ {
+ struct timeval connectTimeout;
+ connectTimeout.tv_sec = 1;
+ connectTimeout.tv_usec = 0;
+ connectWithTimeout(camSock, (struct sockaddr *) &selfAddr, sockAddrSize, &connectTimeout);
+ }
+ }
+}
+
+/**
+ * Start the task that is responsible for sending images to the PC.
+ */
+int PCVideoServer::StartServerTask()
+{
+ if (StatusIsFatal())
+ {
+ return -1;
+ }
+ int id = 0;
+ m_stopServer = false;
+ // Check for prior copy of running task
+ int oldId = taskNameToId((char*)m_serverTask.GetName());
+ if(oldId != ERROR)
+ {
+ // TODO: Report error. You are in a bad state.
+ taskDelete(oldId);
+ }
+
+ // spawn video server task
+ // this is done to ensure that the task is spawned with the
+ // floating point context save parameter.
+ bool started = m_serverTask.Start((int)this);
+
+ id = m_serverTask.GetID();
+
+ if (!started)
+ {
+ wpi_setWPIError(TaskError);
+ return id;
+ }
+ taskDelay(1);
+ return id;
+}
+
+/**
+ * @brief Start sending images to the PC.
+ */
+void PCVideoServer::Start()
+{
+ StartServerTask();
+}
+
+/**
+ * @brief Stop sending images to the PC.
+ */
+void PCVideoServer::Stop()
+{
+ m_stopServer = true;
+}
+
+/**
+ * Static stub for kicking off the server task
+ */
+int PCVideoServer::s_ServerTask(PCVideoServer *thisPtr)
+{
+ return thisPtr->ServerTask();
+}
+
+/**
+ * @brief Initialize the socket and serve images to the PC.
+ * This is the task that serves images to the PC in a loop. This runs
+ * as a separate task.
+ */
+int PCVideoServer::ServerTask()
+{
+ /* Setup to PC sockets */
+ struct sockaddr_in serverAddr;
+ int sockAddrSize = sizeof(serverAddr);
+ int pcSock = ERROR;
+ bzero ((char *) &serverAddr, sockAddrSize);
+ serverAddr.sin_len = (u_char) sockAddrSize;
+ serverAddr.sin_family = AF_INET;
+ serverAddr.sin_port = htons (VIDEO_TO_PC_PORT);
+ serverAddr.sin_addr.s_addr = htonl (INADDR_ANY);
+
+ int success;
+ while (true)
+ {
+ taskSafe();
+ // Create the socket.
+ if ((pcSock = socket (AF_INET, SOCK_STREAM, 0)) == ERROR)
+ {
+ wpi_setErrnoErrorWithContext("Failed to create the PCVideoServer socket");
+ continue;
+ }
+ // Set the TCP socket so that it can be reused if it is in the wait state.
+ int reuseAddr = 1;
+ setsockopt(pcSock, SOL_SOCKET, SO_REUSEADDR, reinterpret_cast<char*>(&reuseAddr), sizeof(reuseAddr));
+ // Bind socket to local address.
+ if (bind (pcSock, (struct sockaddr *) &serverAddr, sockAddrSize) == ERROR)
+ {
+ wpi_setErrnoErrorWithContext("Failed to bind the PCVideoServer port");
+ close (pcSock);
+ continue;
+ }
+ // Create queue for client connection requests.
+ if (listen (pcSock, 1) == ERROR)
+ {
+ wpi_setErrnoErrorWithContext("Failed to listen on the PCVideoServer port");
+ close (pcSock);
+ continue;
+ }
+
+ struct sockaddr_in clientAddr;
+ int clientAddrSize;
+ int newPCSock = accept (pcSock, reinterpret_cast<sockaddr*>(&clientAddr), &clientAddrSize);
+ if (newPCSock == ERROR)
+ {
+ close(pcSock);
+ continue;
+ }
+ //TODO: check camera error
+
+ // Report usage when there is actually a connection.
+ nUsageReporting::report(nUsageReporting::kResourceType_PCVideoServer, 0);
+
+ int numBytes = 0;
+ int imageDataSize = 0;
+ char* imageData = NULL;
+
+ while(!m_stopServer)
+ {
+ success = semTake(m_newImageSem, 1000);
+ if (success == ERROR)
+ {
+ // If the semTake timed out, there are no new images from the camera.
+ continue;
+ }
+ success = AxisCamera::GetInstance().CopyJPEG(&imageData, numBytes, imageDataSize);
+ if (!success)
+ {
+ // No point in running too fast -
+ Wait(1.0);
+ // If camera is not initialzed you will get failure and
+ // the timestamp is invalid. Reset this value and try again.
+ continue;
+ }
+
+ // Write header to PC
+ static const char header[4]={1,0,0,0};
+ int headerSend = write(newPCSock, const_cast<char*>(header), 4);
+
+ // Write image length to PC
+ int lengthSend = write(newPCSock, reinterpret_cast<char*>(&numBytes), 4);
+
+ // Write image to PC
+ int sent = write (newPCSock, imageData, numBytes);
+
+ // The PC probably closed connection. Get out of here
+ // and try listening again.
+ if (headerSend == ERROR || lengthSend == ERROR || sent == ERROR)
+ {
+ break;
+ }
+ }
+ // Clean up
+ delete [] imageData;
+ close (newPCSock);
+ newPCSock = ERROR;
+ close (pcSock);
+ pcSock = ERROR;
+ taskUnsafe();
+ Wait(0.1);
+ }
+ return (OK);
+}
+
diff --git a/aos/externals/WPILib/WPILib/Vision/PCVideoServer.h b/aos/externals/WPILib/WPILib/Vision/PCVideoServer.h
new file mode 100644
index 0000000..875adb8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/PCVideoServer.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __PC_VIDEO_SERVER_H__
+#define __PC_VIDEO_SERVER_H__
+
+#include "Task.h"
+#include <semLib.h>
+
+/** port for sending video to laptop */
+#define VIDEO_TO_PC_PORT 1180
+
+/**
+ * Class the serves images to the PC.
+ */
+class PCVideoServer : public ErrorBase {
+
+public:
+ PCVideoServer();
+ ~PCVideoServer();
+ unsigned int Release();
+ void Start();
+ void Stop();
+
+private:
+ static int s_ServerTask(PCVideoServer *thisPtr);
+ int ServerTask();
+ int StartServerTask();
+
+ Task m_serverTask;
+ SEM_ID m_newImageSem;
+ bool m_stopServer;
+};
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Vision/RGBImage.cpp b/aos/externals/WPILib/WPILib/Vision/RGBImage.cpp
new file mode 100644
index 0000000..a5386a0
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/RGBImage.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "RGBImage.h"
+
+/**
+ * Create a new image that uses Red, Green, and Blue planes.
+ */
+RGBImage::RGBImage() : ColorImage(IMAQ_IMAGE_RGB)
+{
+}
+
+/**
+ * Create a new image by loading a file.
+ * @param fileName The path of the file to load.
+ */
+RGBImage::RGBImage(const char *fileName) : ColorImage(IMAQ_IMAGE_RGB)
+{
+ int success = imaqReadFile(m_imaqImage, fileName, NULL, NULL);
+ wpi_setImaqErrorWithContext(success, "Imaq ReadFile error");
+}
+
+RGBImage::~RGBImage()
+{
+}
diff --git a/aos/externals/WPILib/WPILib/Vision/RGBImage.h b/aos/externals/WPILib/WPILib/Vision/RGBImage.h
new file mode 100644
index 0000000..a92dc58
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/RGBImage.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __RGB_IMAGE_H__
+#define __RGB_IMAGE_H__
+
+#include "ColorImage.h"
+
+/**
+ * A color image represented in RGB color space at 3 bytes per pixel.
+ */
+class RGBImage : public ColorImage
+{
+public:
+ RGBImage();
+ RGBImage(const char *fileName);
+ virtual ~RGBImage();
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Vision/Threshold.cpp b/aos/externals/WPILib/WPILib/Vision/Threshold.cpp
new file mode 100644
index 0000000..8d428e4
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/Threshold.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Threshold.h"
+
+Threshold::Threshold(int new_plane1Low, int new_plane1High, int new_plane2Low,
+ int new_plane2High, int new_plane3Low, int new_plane3High)
+{
+ plane1Low = new_plane1Low;
+ plane1High = new_plane1High;
+ plane2Low = new_plane2Low;
+ plane2High = new_plane2High;
+ plane3Low = new_plane3Low;
+ plane3High = new_plane3High;
+}
diff --git a/aos/externals/WPILib/WPILib/Vision/Threshold.h b/aos/externals/WPILib/WPILib/Vision/Threshold.h
new file mode 100644
index 0000000..c38d7ca
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision/Threshold.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __THRESHOLD_H__
+#define __THRESHOLD_H__
+
+/**
+ * Color threshold values.
+ * This object represnts the threshold values for any type of color object
+ * that is used in a threshhold operation. It simplifies passing values
+ * around in a program for color detection.
+ */
+class Threshold
+{
+public:
+ int plane1Low;
+ int plane1High;
+ int plane2Low;
+ int plane2High;
+ int plane3Low;
+ int plane3High;
+ Threshold(int plane1Low, int plane1High,
+ int plane2Low, int plane2High,
+ int plane3Low, int plane3High);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/Vision2009/AxisCamera.cpp b/aos/externals/WPILib/WPILib/Vision2009/AxisCamera.cpp
new file mode 100644
index 0000000..d5e48cc
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision2009/AxisCamera.cpp
@@ -0,0 +1,1021 @@
+
+/********************************************************************************
+* Project : FIRST Motor Controller
+* File Name : AxisCamera.cpp
+* Contributors : TD, ELF, JDG, SVK
+* Creation Date : July 29, 2008
+* Revision History : Source code & revision history maintained at sourceforge.WPI.edu
+* File Description : Axis camera access for the FIRST Vision API
+* The camera task runs as an independent thread
+*/
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+
+#include "sockLib.h"
+#include "vxWorks.h"
+
+#include "errno.h"
+#include "fioLib.h"
+#include "hostLib.h"
+#include "inetLib.h"
+#include "signal.h"
+#include "sigLib.h" // for signal
+#include <string>
+#include "time.h"
+#include "usrLib.h"
+
+#include "AxisCamera.h"
+#include "BaeUtilities.h"
+#include "FrcError.h"
+#include "Task.h"
+#include "Timer.h"
+#include "VisionAPI.h"
+
+/** packet size */
+#define DEFAULT_PACKET_SIZE 512
+
+/** Private NI function to decode JPEG */
+IMAQ_FUNC int Priv_ReadJPEGString_C(Image* _image, const unsigned char* _string, UINT32 _stringLength);
+
+// To locally enable debug printing: set AxisCamera_debugFlag to a 1, to disable set to 0
+int AxisCamera_debugFlag = 0;
+#define DPRINTF if(AxisCamera_debugFlag)dprintf
+
+/** @brief Camera data to be accessed globally */
+struct {
+ int readerPID; // Set to taskID for signaling
+ int index; /* -1,0,1 */
+ int acquire; /* 0:STOP CAMERA; 1:START CAMERA */
+ int cameraReady; /* 0: CAMERA NOT INITIALIZED; 1: CAMERA INITIALIZED */
+ int decode; /* 0:disable decoding; 1:enable decoding to HSL Image */
+ struct {
+ //
+ // To find the latest image timestamp, access:
+ // globalCamera.data[globalCamera.index].timestamp
+ //
+ double timestamp; // when image was taken
+ char* cameraImage; // jpeg image string
+ int cameraImageSize; // image size
+ Image* decodedImage; // image decoded to NI Image object
+ int decodedImageSize; // size of decoded image
+ }data[2];
+ int cameraMetrics[CAM_NUM_METRICS];
+}globalCamera;
+
+/* run flag */
+static short cont = 0;
+
+/**
+ * @brief Get the most recent camera image.
+ * Supports IMAQ_IMAGE_RGB and IMAQ_IMAGE_HSL.
+ * @param image Image to return to; image must have been first created using frcCreateImage.
+ * When you are done, use frcDispose.
+ * @param timestamp Timestamp to return; will record the time at which the image was stored.
+ * @param lastImageTimestamp Input - timestamp of last image; prevents serving of stale images
+ * @return 0 is failure, 1 is success
+ * @sa frcCreateImage(), frcDispose()
+ */
+int GetImageBlocking(Image* image, double *timestamp, double lastImageTimestamp)
+{
+ char funcName[]="GetImageBlocking";
+ int success;
+ double startTime = GetTime();
+
+ while (1)
+ {
+ success = GetImage(image, timestamp);
+ if (!success) return (success);
+
+ if (*timestamp > lastImageTimestamp)
+ return (1); // GOOD IMAGE RETURNED
+
+ if (GetTime() > (startTime + MAX_BLOCKING_TIME_SEC))
+ {
+ imaqSetError(ERR_CAMERA_BLOCKING_TIMEOUT, funcName);
+ globalCamera.cameraMetrics[CAM_BLOCKING_TIMEOUT]++;
+ return (0); // NO IMAGE AVAILABLE WITHIN specified time
+ }
+ globalCamera.cameraMetrics[CAM_BLOCKING_COUNT]++;
+ taskDelay (1);
+ }
+}
+
+/**
+ * @brief Verifies that the camera is initialized
+ * @return 0 for failure, 1 for success
+ */
+int CameraInitialized()
+{
+ char funcName[]="CameraInitialized";
+ int success = 0;
+ /* check to see if camera is initialized */
+ if (!globalCamera.cameraReady) {
+ imaqSetError(ERR_CAMERA_NOT_INITIALIZED, funcName);
+ DPRINTF (LOG_DEBUG, "Camera request before camera is initialized");
+ globalCamera.cameraMetrics[CAM_GETIMAGE_BEFORE_INIT]++;
+ globalCamera.cameraMetrics[CAM_GETIMAGE_FAILURE]++;
+ return success;
+ }
+
+ if (globalCamera.index == -1){
+ imaqSetError(ERR_CAMERA_NO_BUFFER_AVAILABLE, funcName);
+ DPRINTF (LOG_DEBUG, "No camera image available");
+ globalCamera.cameraMetrics[CAM_GETIMAGE_BEFORE_AVAILABLE]++;
+ globalCamera.cameraMetrics[CAM_GETIMAGE_FAILURE]++;
+ return success;
+ }
+ return 1;
+}
+
+/**
+ * @brief Gets the most recent camera image, as long as it is not stale.
+ * Supported image types: IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL
+ * @param image Image to return, must have first been created with frcCreateImage or imaqCreate.
+ * When you finish with the image, call frcDispose() to dispose of it.
+ * @param timestamp Returned timestamp of when the image was taken from the camera
+ * @return failure = 0, success = 1
+ */
+int GetImage(Image* image, double *timestamp)
+{
+ char funcName[]="GetImage";
+ int success = 0;
+ int readIndex;
+ int readCount = 10;
+ double currentTime = time(NULL);
+ double currentImageTimestamp;
+
+ /* check to see if camera is initialized */
+
+ if (!CameraInitialized()) {return success;}
+
+ /* try readCount times to get an image */
+ while (readCount) {
+ readIndex = globalCamera.index;
+ if (!imaqDuplicate(image, globalCamera.data[readIndex].decodedImage)) {
+ int errorCode = GetLastVisionError();
+ DPRINTF (LOG_DEBUG,"Error duplicating image= %i %s ", errorCode, GetVisionErrorText(errorCode));
+ }
+ // save the timestamp to check before returning
+ currentImageTimestamp = globalCamera.data[readIndex].timestamp;
+
+ // make sure this buffer is not being written to now
+ if (readIndex == globalCamera.index) break;
+ readCount--;
+ }
+
+ /* were we successful ? */
+ if (readCount){
+ success = 1;
+ if (timestamp != NULL)
+ *timestamp = currentImageTimestamp; // Return image timestamp
+ } else{
+ globalCamera.cameraMetrics[CAM_GETIMAGE_FAILURE]++;
+ }
+
+ /* Ensure the buffered image is not too old - set this "stale time" above */
+ if (currentTime > globalCamera.data[globalCamera.index].timestamp + CAMERA_IMAGE_STALE_TIME_SEC){
+ DPRINTF (LOG_CRITICAL, "STALE camera image (THIS COULD BE A BAD IMAGE)");
+ imaqSetError(ERR_CAMERA_STALE_IMAGE, funcName);
+ globalCamera.cameraMetrics[CAM_STALE_IMAGE]++;
+ globalCamera.cameraMetrics[CAM_GETIMAGE_FAILURE]++;
+ success = 0;
+ }
+ globalCamera.cameraMetrics[CAM_GETIMAGE_SUCCESS]++;
+ return success;
+}
+
+/**
+ * @brief Method to get a raw image from the buffer
+ * @param imageData returned image data
+ * @param numBytes returned number of bytes in buffer
+ * @param currentImageTimestamp returned buffer time of image data
+ * @return 0 if failure; 1 if success
+ */
+int GetImageData(char** imageData, int* numBytes, double* currentImageTimestamp)
+{
+ int success = 0;
+ int readIndex;
+ int readCount = 10;
+ int cameraImageSize;
+ char *cameraImageString;
+
+ /* check to see if camera is initialized */
+
+ if (!CameraInitialized()) {return success;}
+
+ /* try readCount times to get an image */
+ while (readCount) {
+ readIndex = globalCamera.index;
+ cameraImageSize = globalCamera.data[readIndex].cameraImageSize;
+ //cameraImageString = (Image *) malloc(cameraImageSize);
+ cameraImageString = new char[cameraImageSize];
+ if (NULL == cameraImageString) {
+ DPRINTF (LOG_DEBUG, "Unable to allocate cameraImage");
+ globalCamera.cameraMetrics[CAM_GETIMAGE_FAILURE]++;
+ return success;
+ }
+ memcpy (cameraImageString, globalCamera.data[readIndex].cameraImage, cameraImageSize);
+ *currentImageTimestamp = globalCamera.data[readIndex].timestamp;
+ // make sure this buffer is not being written to now
+ if (readIndex == globalCamera.index) break;
+ free (cameraImageString);
+ readCount--;
+ }
+ if (readCount){
+ *imageData = cameraImageString;
+ *numBytes = cameraImageSize;
+ return 1;
+ }
+ return (OK);
+}
+
+/**
+ * @brief Blocking call to get images for PC.
+ * This should be called from a separate task to maintain camera read performance.
+ * It is intended to be used for sending raw (undecoded) image data to the PC.
+ * @param imageData image data to return
+ * @param numBytes number of bytes in buffer
+ * @param timestamp timestamp of buffer returned
+ * @param lastImageTimestamp buffer time of last image data sent to PC
+ * @return 0 if failure; 1 if success
+ */
+int GetImageDataBlocking(char** imageData, int* numBytes, double* timestamp, double lastImageTimestamp)
+{
+
+ char funcName[]="GetImageDataBlocking";
+ int success;
+ double startTime = GetTime();
+
+ *imageData = NULL;
+ while (1)
+ {
+ success = GetImageData(imageData, numBytes, timestamp);
+ if (!success) return (success);
+
+ if (*timestamp > lastImageTimestamp)
+ return (1); // GOOD IMAGE DATA RETURNED
+
+ delete *imageData;
+ *imageData = NULL;
+
+ if (GetTime() > (startTime + MAX_BLOCKING_TIME_SEC))
+ {
+ imaqSetError(ERR_CAMERA_BLOCKING_TIMEOUT, funcName);
+ return (0); // NO IMAGE AVAILABLE WITHIN specified time
+ }
+ globalCamera.cameraMetrics[CAM_BLOCKING_COUNT]++;
+ taskDelay (1);
+ }
+}
+
+/**
+ * @brief Accessor for camera instrumentation data
+ * @param the counter queried
+ * @return the counter value
+ */
+int GetCameraMetric(FrcvCameraMetric metric)
+{ return globalCamera.cameraMetrics[metric]; }
+
+/**
+ * @brief Close socket & report error
+ * @param errstring String to print
+ * @param socket Socket to close
+ * @return error
+ */
+int CameraCloseSocket(char *errstring, int socket)
+{
+ DPRINTF (LOG_CRITICAL, "Closing socket - CAMERA ERROR: %s", errstring );
+ close (socket);
+ return (ERROR);
+}
+
+
+/**
+ * @brief Reads one line from the TCP stream.
+ * @param camSock The socket.
+ * @param buffer A buffer with bufSize allocated for it.
+ * On return, bufSize-1 amount of data or data upto first line ending
+ * whichever is smaller, null terminated.
+ * @param bufSize The size of buffer.
+ * @param stripLineEnding If true, strips the line ending chacters from the buffer before return.
+ * @return 0 if failure; 1 if success
+*/
+static int CameraReadLine(int camSock, char* buffer, int bufSize, bool stripLineEnding) {
+ char funcName[]="CameraReadLine";
+ // Need at least 3 bytes in the buffer to pull this off.
+ if (bufSize < 3) {
+ imaqSetError(ERR_CAMERA_FAILURE, funcName);
+ return 0;
+ }
+ // Reduce size by 1 to allow for null terminator.
+ --bufSize;
+ // Read upto bufSize characters.
+ for (int i=0;i < bufSize;++i, ++buffer) {
+ // Read one character.
+ if (read (camSock, buffer, 1) <= 0) {
+ imaqSetError(ERR_CAMERA_FAILURE, funcName);
+ return 0;
+ }
+ // Line endings can be "\r\n" or just "\n". So always
+ // look for a "\n". If you got just a "\n" and
+ // stripLineEnding is false, then convert it into a \r\n
+ // because callers expect a \r\n.
+ // If the combination of the previous character and the current character
+ // is "\r\n", the line ending
+ if (*buffer=='\n') {
+ // If asked to strip the line ending, then set the buffer to the previous
+ // character.
+ if (stripLineEnding) {
+ if (i > 0 && *(buffer-1)=='\r') {
+ --buffer;
+ }
+ }
+ else {
+ // If the previous character was not a '\r',
+ if (i == 0 || *(buffer-1)!='\r') {
+ // Make the current character a '\r'.
+ *buffer = '\r';
+ // If space permits, add back the '\n'.
+ if (i < bufSize-1) {
+ ++buffer;
+ *buffer = '\n';
+ }
+ }
+ // Set the buffer past the current character ('\n')
+ ++buffer;
+ }
+ break;
+ }
+ }
+ // Null terminate.
+ *buffer = '\0';
+ return 1;
+}
+
+/**
+@brief Skips read data until the first empty line.
+
+@param camSock An open tcp socket to the camera to read the data from.
+@return sucess 0 if failure; 1 if success
+*/
+static int CameraSkipUntilEmptyLine(int camSock) {
+ char buffer[1024];
+ int success = 0;
+ while(1) {
+ success = CameraReadLine(camSock, buffer, sizeof(buffer), true);
+ if (*buffer == '\0') {
+ return success;
+ }
+ }
+ return success;
+}
+
+/**
+@brief Opens a socket.
+
+Issues the given http request with the required added information
+and authentication. It cycles through an array of predetermined
+encrypted username, password combinations that we expect the users
+to have at any point in time. If none of the username, password
+combinations work, it outputs a "Unknown user or password" error.
+If the request succeeds, it returns the socket number.
+
+@param serverName The information about the host from which this request originates
+@param request The request to send to the camera not including boilerplate or
+ authentication. This is usually in the form of "GET <string>"
+@return int - failure = ERROR; success = socket number;
+*/
+static int CameraOpenSocketAndIssueAuthorizedRequest(const char* serverName, const char* request)
+{
+ char funcName[]="cameraOpenSocketAndIssueAuthorizedRequest";
+
+ struct sockaddr_in cameraAddr;
+ int sockAddrSize;
+ int camSock = ERROR;
+
+ // The camera is expected to have one of the following username, password combinations.
+ // This routine will return an error if it does not find one of these.
+ static const char* authenticationStrings[] = {
+ "RlJDOkZSQw==", /* FRC, FRC */
+ "cm9vdDpwYXNz", /* root, admin*/
+ "cm9vdDphZG1pbg==" /* root, pass*/
+ };
+
+ static const int numAuthenticationStrings = sizeof(authenticationStrings)/sizeof(authenticationStrings[0]);
+
+ static const char *requestTemplate = "%s " \
+ "HTTP/1.1\n" \
+ "User-Agent: HTTPStreamClient\n" \
+ "Connection: Keep-Alive\n" \
+ "Cache-Control: no-cache\n" \
+ "Authorization: Basic %s\n\n";
+
+ int i = 0;
+ for (;i < numAuthenticationStrings;++i) {
+ char buffer[1024];
+
+ sprintf(buffer, requestTemplate, request, authenticationStrings[i]);
+
+ /* create camera socket */
+ //DPRINTF (LOG_DEBUG, "creating camSock" );
+ if ((camSock = socket (AF_INET, SOCK_STREAM, 0)) == ERROR) {
+ imaqSetError(ERR_CAMERA_SOCKET_CREATE_FAILED, funcName);
+ perror("Failed to create socket");
+ return (ERROR);
+ }
+
+ sockAddrSize = sizeof (struct sockaddr_in);
+ bzero ((char *) &cameraAddr, sockAddrSize);
+ cameraAddr.sin_family = AF_INET;
+ cameraAddr.sin_len = (u_char) sockAddrSize;
+ cameraAddr.sin_port = htons (CAMERA_PORT);
+
+ if (( (int)(cameraAddr.sin_addr.s_addr = inet_addr (const_cast<char*>(serverName)) ) == ERROR) &&
+ ( (int)(cameraAddr.sin_addr.s_addr = hostGetByName (const_cast<char*>(serverName)) ) == ERROR))
+ {
+ imaqSetError(ERR_CAMERA_CONNECT_FAILED, funcName);
+ return CameraCloseSocket("Failed to get IP, check hostname or IP", camSock);
+ }
+
+ //DPRINTF (LOG_INFO, "connecting camSock" );
+ if (connect (camSock, (struct sockaddr *) &cameraAddr, sockAddrSize) == ERROR) {
+ imaqSetError(ERR_CAMERA_CONNECT_FAILED, funcName);
+ return CameraCloseSocket("Failed to connect to camera - check networ", camSock);
+ }
+
+ //DPRINTF (LOG_DEBUG, "writing GET request to camSock" );
+ if (write (camSock, buffer, strlen(buffer) ) == ERROR) {
+ imaqSetError(ERR_CAMERA_CONNECT_FAILED, funcName);
+ return CameraCloseSocket("Failed to send GET request", camSock);
+ }
+
+ // Read one line with the line ending removed.
+ if (!CameraReadLine(camSock, buffer, 1024, true)) {
+ return CameraCloseSocket("Bad response to GET request", camSock);
+ }
+
+ // Check if the response is of the format HTTP/<version> 200 OK.
+ float discard;
+ if (sscanf(buffer, "HTTP/%f 200 OK", &discard) == 1) {
+ break;
+ }
+
+ // We have to close the connection because in the case of failure
+ // the server closes the connection.
+ close(camSock);
+ }
+ // If none of the attempts were successful, then let the caller know.
+ if (numAuthenticationStrings == i) {
+ imaqSetError(ERR_CAMERA_AUTHORIZATION_FAILED, funcName);
+ fprintf(stderr, "Expected username/password combination not found on camera");
+ return ERROR;
+ }
+ return camSock;
+}
+
+
+/**
+ * @brief Sends a configuration message to the camera
+ * @param configString configuration message to the camera
+ * @return success: 0=failure; 1=success
+ */
+int ConfigureCamera(char *configString){
+ char funcName[]="ConfigureCamera";
+ char *serverName = "192.168.0.90"; /* camera @ */
+ int success = 0;
+ int camSock = 0;
+
+ /* Generate camera configuration string */
+ char * getStr1 =
+ "GET /axis-cgi/admin/param.cgi?action=update&ImageSource.I0.Sensor.";
+
+ char cameraRequest[strlen(getStr1) + strlen(configString)];
+ sprintf (cameraRequest, "%s%s", getStr1, configString);
+ DPRINTF(LOG_DEBUG, "camera configuration string: \n%s", cameraRequest);
+ camSock = CameraOpenSocketAndIssueAuthorizedRequest(serverName, cameraRequest);
+ DPRINTF(LOG_DEBUG, "camera socket# = %i", camSock);
+
+ //read response
+ success = CameraSkipUntilEmptyLine(camSock);
+ //DPRINTF(LOG_DEBUG, "succcess from CameraSkipUntilEmptyLine: %i", success);
+ char buffer[3]; // set property - 3
+ success = CameraReadLine(camSock, buffer, 3, true);
+ //DPRINTF(LOG_DEBUG, "succcess from CameraReadLine: %i", success);
+ DPRINTF(LOG_DEBUG, "line read from camera \n%s", buffer);
+ if (strcmp(buffer, "OK") != 0) {
+ imaqSetError(ERR_CAMERA_COMMAND_FAILURE, funcName);
+ DPRINTF(LOG_DEBUG, "setting ERR_CAMERA_COMMAND_FAILURE - OK not found");
+ }
+ DPRINTF (LOG_INFO, "\nConfigureCamera ENDING success = %i\n", success );
+
+ /* clean up */
+ close (camSock);
+ return (1);
+}
+
+
+/**
+ * @brief Sends a request message to the camera
+ * @param configString request message to the camera
+ * @param cameraResponse response from camera
+ * @return success: 0=failure; 1=success
+ */
+int GetCameraSetting(char *configString, char *cameraResponse){
+ char *serverName = "192.168.0.90"; /* camera @ */
+ int success = 0;
+ int camSock = 0;
+
+ /* Generate camera request string */
+ char * getStr1 =
+ "GET /axis-cgi/admin/param.cgi?action=list&group=ImageSource.I0.Sensor.";
+ char cameraRequest[strlen(getStr1) + strlen(configString)];
+ sprintf (cameraRequest, "%s%s", getStr1, configString);
+ DPRINTF(LOG_DEBUG, "camera configuration string: \n%s", cameraRequest);
+ camSock = CameraOpenSocketAndIssueAuthorizedRequest(serverName, cameraRequest);
+ DPRINTF(LOG_DEBUG, "return from CameraOpenSocketAndIssueAuthorizedRequest %i", camSock);
+
+ //read response
+ success = CameraSkipUntilEmptyLine(camSock);
+ success = CameraReadLine(camSock, cameraResponse, 1024, true);
+ DPRINTF(LOG_DEBUG, "succcess from CameraReadLine: %i", success);
+ DPRINTF(LOG_DEBUG, "line read from camera \n%s", cameraResponse);
+ DPRINTF (LOG_INFO, "\nGetCameraSetting ENDING success = %i\n", success );
+
+ /* clean up */
+ close (camSock);
+ return (1);
+}
+
+/**
+ * @brief Sends a request message to the camera for image appearance property
+ * (resolution, compression, rotation)
+ * @param configString request message to the camera
+ * @param cameraResponse response from camera
+ * @return success: 0=failure; 1=success
+ */
+int GetImageSetting(char *configString, char *cameraResponse){
+ char *serverName = "192.168.0.90"; /* camera @ */
+ int success = 0;
+ int camSock = 0;
+
+ /* Generate camera request string */
+ char *getStr1 = "GET /axis-cgi/admin/param.cgi?action=list&group=Image.I0.Appearance.";
+ char cameraRequest[strlen(getStr1) + strlen(configString)];
+ sprintf (cameraRequest, "%s%s", getStr1, configString);
+ DPRINTF(LOG_DEBUG, "camera configuration string: \n%s", cameraRequest);
+ camSock = CameraOpenSocketAndIssueAuthorizedRequest(serverName, cameraRequest);
+ DPRINTF(LOG_DEBUG, "return from CameraOpenSocketAndIssueAuthorizedRequest %i", camSock);
+
+ //read response
+ success = CameraSkipUntilEmptyLine(camSock);
+ success = CameraReadLine(camSock, cameraResponse, 1024, true);
+ DPRINTF(LOG_DEBUG, "succcess from CameraReadLine: %i", success);
+ DPRINTF(LOG_DEBUG, "line read from camera \n%s", cameraResponse);
+ DPRINTF (LOG_INFO, "\nGetCameraSetting ENDING success = %i\n", success );
+
+ /* clean up */
+ close (camSock);
+ return (1);
+}
+
+
+#define MEASURE_SOCKET_TIME 1
+
+/**
+ * @brief Manage access to the camera. Sets up sockets and reads images
+ * @param frames Frames per second
+ * @param compression Camera image compression
+ * @param resolution Camera image size
+ * @param rotation Camera image rotation
+ * @return error
+ */
+int cameraJPEGServer(int frames, int compression, ImageResolution resolution, ImageRotation rotation)
+{
+ char funcName[]="cameraJPEGServer";
+ char *serverName = "192.168.0.90"; /* camera @ */
+ cont = 1;
+ int errorCode = 0;
+ int printCounter = 0;
+ int writeIndex;
+ int authorizeCount = 0;
+ int authorizeConfirmed = 0;
+ static const int authenticationStringsCount = 3;
+ static const char* authenticationStrings[] = {
+ "cm9vdDphZG1pbg==", /* root, admin*/
+ "RlJDOkZSQw==", /* FRC, FRC */
+ "cm9vdDpwYXNz==" /* root, pass*/
+ };
+
+ DPRINTF (LOG_DEBUG, "cameraJPEGServer" );
+
+ struct sockaddr_in cameraAddr;
+ int sockAddrSize;
+ int camSock = 0;
+
+ char resStr[10];
+ switch (resolution) {
+ case k640x480: { sprintf(resStr,"640x480"); break; }
+ case k320x240: { sprintf(resStr,"320x240"); break; }
+ case k160x120: { sprintf(resStr,"160x120"); break; }
+ default: {DPRINTF (LOG_DEBUG, "code error - resolution input" ); break; }
+ }
+
+ /* Generate camera initialization string */
+ /* changed resolution to 160x120 from 320x240 */
+ /* supported resolutions are: 640x480, 640x360, 320x240, 160x120 */
+ char * getStr1 =
+ "GET /axis-cgi/mjpg/video.cgi?showlength=1&camera=1&";
+
+ char insertStr[100];
+ sprintf (insertStr, "des_fps=%i&compression=%i&resolution=%s&rotation=%i",
+ frames, compression, resStr, (int)rotation);
+
+ char * getStr2 = " HTTP/1.1\n\
+User-Agent: HTTPStreamClient\n\
+Host: 192.150.1.100\n\
+Connection: Keep-Alive\n\
+Cache-Control: no-cache\n\
+Authorization: Basic %s;\n\n";
+
+ char getStr[strlen(getStr1) + strlen(insertStr) + strlen(getStr2)];
+ sprintf (getStr, "%s:%s%s", getStr1, insertStr, getStr2);
+
+ DPRINTF(LOG_DEBUG, "revised camera string: \n%s", getStr);
+ /* Allocation */
+ char tempBuffer[1024];
+
+ RETRY:
+ Wait(0.1); //bug fix - don't pester camera if it's booting
+ while (globalCamera.acquire == 0) Wait(0.1);
+
+ if (!authorizeConfirmed){
+ if (authorizeCount < authenticationStringsCount){
+ sprintf (tempBuffer, getStr, authenticationStrings[authorizeCount]);
+ } else {
+ imaqSetError(ERR_CAMERA_AUTHORIZATION_FAILED, funcName);
+ fprintf(stderr, "Camera authorization failed ... Incorrect password on camera!!");
+ return (ERROR);
+ }
+ }
+
+ while (1)
+ {
+ globalCamera.cameraMetrics[CAM_SOCKET_INIT_ATTEMPTS]++;
+
+ /* create camera socket */
+ DPRINTF (LOG_DEBUG, "creating camSock" );
+ if ((camSock = socket (AF_INET, SOCK_STREAM, 0)) == ERROR) {
+ imaqSetError(ERR_CAMERA_SOCKET_CREATE_FAILED, funcName);
+ perror("Failed to create socket");
+ cont = 0;
+ return (ERROR);
+ }
+
+ sockAddrSize = sizeof (struct sockaddr_in);
+ bzero ((char *) &cameraAddr, sockAddrSize);
+ cameraAddr.sin_family = AF_INET;
+ cameraAddr.sin_len = (u_char) sockAddrSize;
+ cameraAddr.sin_port = htons (CAMERA_PORT);
+
+ DPRINTF (LOG_DEBUG, "getting IP" );
+ if (( (int)(cameraAddr.sin_addr.s_addr = inet_addr (serverName) ) == ERROR) &&
+ ( (int)(cameraAddr.sin_addr.s_addr = hostGetByName (serverName) ) == ERROR))
+ {
+ CameraCloseSocket("Failed to get IP, check hostname or IP", camSock);
+ continue;
+ }
+
+ DPRINTF (LOG_INFO, "Attempting to connect to camSock" );
+ if (connect (camSock, (struct sockaddr *) &cameraAddr, sockAddrSize) == ERROR) {
+ imaqSetError(ERR_CAMERA_CONNECT_FAILED, funcName);
+ CameraCloseSocket("Failed to connect to camera - check network", camSock);
+ continue;
+ }
+
+#if MEASURE_SOCKET_SETUP
+ socketEndTime = GetTime();
+ setupTime = socketEndTime - socketStartTime;
+ printf("\n***socket setup time = %g\n", setupTime );
+#endif
+
+ globalCamera.cameraMetrics[CAM_SOCKET_OPEN]++;
+ break;
+ } // end while (trying to connect to camera)
+
+ DPRINTF (LOG_DEBUG, "writing GET request to camSock" );
+ if (write (camSock, tempBuffer , strlen(tempBuffer) ) == ERROR) {
+ return CameraCloseSocket("Failed to send GET request", camSock);
+ }
+
+ //DPRINTF (LOG_DEBUG, "reading header" );
+ /* Find content-length, then read that many bytes */
+ int counter = 2;
+ char* contentString = "Content-Length: ";
+ char* authorizeString = "200 OK";
+
+#define MEASURE_TIME 0
+#if MEASURE_TIME
+ //timing parameters - only measure one at the time
+ double loopStartTime = 0.0; // measuring speed of execution loop
+ double loopEndTime = 0.0;
+ double cameraStartTime = 0.0;
+ double cameraEndTime = 0.0;
+ double previousStartTime = 0.0;
+ int performanceLoopCounter = 0;
+ int maxCount = 30;
+#endif
+
+ while (cont) {
+#if MEASURE_TIME
+ previousStartTime = loopStartTime; // first time is bogus
+ loopStartTime = GetTime();
+#endif
+ // If camera has been turned OFF, jump to RETRY
+ //if (globalCamera.acquire == 0) goto RETRY;
+
+ /* Determine writer index */
+ if (globalCamera.index == 0)
+ writeIndex = 1;
+ else
+ writeIndex = 0;
+
+ /* read header */
+ //TODO: check for error in header, increment ERR_CAMERA_HEADER_ERROR
+ char initialReadBuffer[DEFAULT_PACKET_SIZE] = "";
+ char intermediateBuffer[1];
+ char *trailingPtr = initialReadBuffer;
+ int trailingCounter = 0;
+
+
+#if MEASURE_TIME
+ cameraStartTime = GetTime();
+#endif
+
+ while (counter) {
+ if (read (camSock, intermediateBuffer, 1) <= 0) {
+ CameraCloseSocket("Failed to read image header", camSock);
+ globalCamera.cameraMetrics[ERR_CAMERA_HEADER_ERROR]++;
+ goto RETRY;
+ }
+
+ strncat(initialReadBuffer, intermediateBuffer, 1);
+ if (NULL != strstr(trailingPtr, "\r\n\r\n")) {
+
+ if (!authorizeConfirmed){
+
+ if (strstr(initialReadBuffer, authorizeString))
+ {
+ authorizeConfirmed = 1;
+ /* set camera to initialized */
+ globalCamera.cameraReady = 1;
+ }
+ else
+ {
+ CameraCloseSocket("Not authorized to connect to camera", camSock);
+ authorizeCount++;
+ goto RETRY;
+ }
+ }
+ --counter;
+ }
+ if (++trailingCounter >= 4) {
+ trailingPtr++;
+ }
+ }
+
+ counter = 1;
+ char *contentLength = strstr(initialReadBuffer, contentString);
+ if (contentLength == NULL) {
+ globalCamera.cameraMetrics[ERR_CAMERA_HEADER_ERROR]++;
+ CameraCloseSocket("No content-length token found in packet", camSock);
+ goto RETRY;
+ }
+ /* get length of image content */
+ contentLength = contentLength + strlen(contentString);
+ globalCamera.data[writeIndex].cameraImageSize = atol (contentLength);
+
+ if(globalCamera.data[writeIndex].cameraImage)
+ free(globalCamera.data[writeIndex].cameraImage);
+ //globalCamera.data[writeIndex].cameraImage = (Image *) malloc(globalCamera.data[writeIndex].cameraImageSize);
+ globalCamera.data[writeIndex].cameraImage = (char*)malloc(globalCamera.data[writeIndex].cameraImageSize);
+ if (NULL == globalCamera.data[writeIndex].cameraImage) {
+ return CameraCloseSocket("Failed to allocate space for imageString", camSock);
+ }
+ globalCamera.cameraMetrics[CAM_BUFFERS_WRITTEN]++;
+
+ //
+ // This is a blocking camera read function, and will block if the camera
+ // has been disconnected from the cRIO. If however the camera is
+ // POWERED OFF while connected to the cRIO, this function NEVER RETURNS
+ //
+ int bytesRead = fioRead (camSock, (char *)globalCamera.data[writeIndex].cameraImage,
+ globalCamera.data[writeIndex].cameraImageSize);
+
+#if MEASURE_TIME
+ cameraEndTime = GetTime();
+#endif
+
+ //DPRINTF (LOG_DEBUG, "Completed fioRead function - bytes read:%d", bytesRead);
+ if (bytesRead <= 0) {
+ CameraCloseSocket("Failed to read image data", camSock);
+ goto RETRY;
+ } else if (bytesRead != globalCamera.data[writeIndex].cameraImageSize){
+ fprintf(stderr, "ERROR: Failed to read entire image: readLength does not match bytes read");
+ globalCamera.cameraMetrics[CAM_BAD_IMAGE_SIZE]++;
+ }
+ // if decoding the JPEG to an HSL Image, do it here
+ if (globalCamera.decode) {
+ if(globalCamera.data[writeIndex].decodedImage)
+ frcDispose(globalCamera.data[writeIndex].decodedImage);
+ globalCamera.data[writeIndex].decodedImage = frcCreateImage(IMAQ_IMAGE_HSL);
+ if (! Priv_ReadJPEGString_C(globalCamera.data[writeIndex].decodedImage,
+ (const unsigned char *)globalCamera.data[writeIndex].cameraImage,
+ globalCamera.data[writeIndex].cameraImageSize) ) {
+ DPRINTF (LOG_DEBUG, "failure creating Image");
+ }
+ }
+
+ // TODO: React to partial image
+ globalCamera.data[writeIndex].timestamp = GetTime();
+ globalCamera.index = writeIndex;
+
+ /* signal a listening task */
+ if (globalCamera.readerPID) {
+ if (taskKill (globalCamera.readerPID,SIGUSR1) == OK)
+ DPRINTF (LOG_DEBUG, "SIGNALING PID= %i", globalCamera.readerPID);
+ else
+ globalCamera.cameraMetrics[CAM_PID_SIGNAL_ERR]++;
+ DPRINTF (LOG_DEBUG, "ERROR SIGNALING PID= %i", globalCamera.readerPID);
+ }
+
+ globalCamera.cameraMetrics[CAM_NUM_IMAGE]++;
+ printCounter ++;
+ if (printCounter == 1000) {
+ DPRINTF (LOG_DEBUG, "imageCounter = %i", globalCamera.cameraMetrics[CAM_NUM_IMAGE]);
+ printCounter=0;
+ }
+
+ taskDelay(1);
+
+#if MEASURE_TIME
+ loopEndTime = GetTime();
+ performanceLoopCounter++;
+ if (performanceLoopCounter <= maxCount) {
+ DPRINTF (LOG_DEBUG, "%i DONE!!!: loop = ,%g, camera = ,%g, difference = ,%g, loopRate= ,%g,",
+ performanceLoopCounter, loopEndTime-loopStartTime, cameraEndTime-cameraStartTime,
+ (loopEndTime-loopStartTime) - (cameraEndTime-cameraStartTime),
+ loopStartTime-previousStartTime);
+ }
+#endif
+ } /* end while (cont) */
+
+ /* clean up */
+ close (camSock);
+ cont = 0;
+ DPRINTF (LOG_INFO, "\nJPEG SERVER ENDING errorCode = %i\n", errorCode );
+
+ return (OK);
+}
+
+/**
+ * @brief Start signaling a task when new images are available
+ * @param taskID number for task to get the signal
+ */
+void StartImageSignal(int taskId) // Start issuing a SIGUSR1 signal to the specified taskId
+{ globalCamera.readerPID = taskId; }
+
+/**
+ * @brief Start serving images
+ */
+void StartImageAcquisition()
+{
+ globalCamera.cameraMetrics[CAM_STARTS]++;
+ globalCamera.acquire = 1;
+ DPRINTF(LOG_DEBUG, "starting acquisition");
+}
+
+
+/**
+ * @brief Stop serving images
+ */
+void StopImageAcquisition()
+{ globalCamera.cameraMetrics[CAM_STOPS]++; globalCamera.acquire = 0; }
+
+
+/**
+ * @brief This is the routine that is run when the task is spawned
+ * It initializes the camera with the image settings passed in, and
+ * starts image acquisition.
+ * @param frames Frames per second
+ * @param compression Camera image compression
+ * @param resolution Camera image size
+ * @param rotation Camera image rotation
+ */
+static int initCamera(int frames, int compression, ImageResolution resolution, ImageRotation rotation)
+{
+ //SetDebugFlag ( DEBUG_SCREEN_AND_FILE ) ;
+
+ DPRINTF(LOG_DEBUG, "\n+++++ camera task starting: rotation = %i", (int)rotation);
+ int errorCode;
+
+ /* Initialize globalCamera area
+ * Set decode to 1 - always want to decode images for processing
+ * If ONLY sending images to the dashboard, you could set it to 0 */
+ bzero ((char *)&globalCamera, sizeof(globalCamera));
+ globalCamera.index = -1;
+ globalCamera.decode = 1;
+
+ /* allow writing to vxWorks target */
+ Priv_SetWriteFileAllowed(1);
+
+ /* start acquisition immediately */
+ StartImageAcquisition();
+
+ /* cameraJPEGServer runs until camera is stopped */
+ DPRINTF (LOG_DEBUG, "calling cameraJPEGServer" );
+ errorCode = cameraJPEGServer(frames, compression, resolution, rotation);
+ DPRINTF (LOG_INFO, "errorCode from cameraJPEGServer = %i\n", errorCode );
+ return (OK);
+}
+
+Task g_axisCameraTask("Camera", (FUNCPTR)initCamera);
+
+/**
+ * @brief Start the camera task
+ * @param frames Frames per second
+ * @param compression Camera image compression
+ * @param resolution Camera image size
+ * @param rotation Camera image rotation (ROT_0 or ROT_180)
+ * @return TaskID of camera task, or -1 if error.
+ */
+int StartCameraTask()
+{
+ return StartCameraTask(10, 0, k160x120, ROT_0);
+}
+int StartCameraTask(int frames, int compression, ImageResolution resolution, ImageRotation rotation)
+{
+ char funcName[]="startCameraTask";
+ DPRINTF(LOG_DEBUG, "starting camera");
+
+ int cameraTaskID = 0;
+
+ //range check
+ if (frames < 1) frames = 1;
+ else if (frames > 30) frames = 30;
+ if (compression < 0) compression = 0;
+ else if (compression > 100) compression = 100;
+
+ // stop any prior copy of running task
+ StopCameraTask();
+
+ // spawn camera task
+ bool started = g_axisCameraTask.Start(frames, compression, resolution, rotation);
+ cameraTaskID = g_axisCameraTask.GetID();
+ DPRINTF(LOG_DEBUG, "spawned task id %i", cameraTaskID);
+
+ if (!started) {
+ DPRINTF(LOG_DEBUG, "camera task failed to start");
+ imaqSetError(ERR_CAMERA_TASK_SPAWN_FAILED, funcName);
+ return -1;
+ }
+ return cameraTaskID;
+}
+
+/**
+ * @brief Stops the camera task
+ * @return TaskID of camera task killed, or -1 if none was running.
+ */
+int StopCameraTask()
+{
+ std::string taskName("FRC_Camera");
+ // check for prior copy of running task
+ int oldTaskID = taskNameToId(const_cast<char*>(taskName.c_str()));
+ if(oldTaskID != ERROR) { taskDelete(oldTaskID); }
+ return oldTaskID;
+}
+
+#if 0
+/* if you want to run this task by itself to debug
+ * enable this code and make RunProgram the entry point
+ */
+extern "C"
+{
+void RunProgram();
+int AxisCamera_StartupLibraryInit();
+}
+/** * @brief Start point of the program */
+void RunProgram()
+{ StartCameraTask();}
+
+/** * @brief This is the main program that is run by the debugger or the robot on boot. */
+int AxisCamera_StartupLibraryInit()
+ { RunProgram(); return 0; }
+
+#endif
+
+
+
diff --git a/aos/externals/WPILib/WPILib/Vision2009/AxisCamera.h b/aos/externals/WPILib/WPILib/Vision2009/AxisCamera.h
new file mode 100644
index 0000000..a6b21d0
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision2009/AxisCamera.h
@@ -0,0 +1,92 @@
+/********************************************************************************
+* Project : FIRST Motor Controller
+* File Name : AxisCamera.h
+* Contributors : ELF
+* Creation Date : August 12, 2008
+* Revision History : Source code & revision history maintained at sourceforge.WPI.edu
+* File Description : Globally defined values for the FRC Camera API
+*
+* API: Because nivision.h uses C++ style comments, any file including this
+* must be a .cpp instead of .c.
+*
+*/
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __AXISCAMERA_H__
+#define __AXISCAMERA_H__
+
+#include "nivision.h"
+
+/** port for communicating with camera */
+#define CAMERA_PORT 80
+/** how old an image is before it's discarded */
+#define CAMERA_IMAGE_STALE_TIME_SEC 2.0
+/** time to wait for a new image in blocking call */
+#define MAX_BLOCKING_TIME_SEC 0.5
+
+/* Enumerated Types */
+/** @brief Counters for camera metrics */
+enum FrcvCameraMetric {CAM_STARTS, CAM_STOPS,
+ CAM_NUM_IMAGE, CAM_BUFFERS_WRITTEN, CAM_BLOCKING_COUNT,
+
+ CAM_SOCKET_OPEN, CAM_SOCKET_INIT_ATTEMPTS, CAM_BLOCKING_TIMEOUT,
+ CAM_GETIMAGE_SUCCESS, CAM_GETIMAGE_FAILURE,
+
+ CAM_STALE_IMAGE, CAM_GETIMAGE_BEFORE_INIT, CAM_GETIMAGE_BEFORE_AVAILABLE,
+ CAM_READ_JPEG_FAILURE, CAM_PID_SIGNAL_ERR,
+
+ CAM_BAD_IMAGE_SIZE, CAM_HEADER_ERROR};
+
+#define CAM_NUM_METRICS 17
+
+/** Private NI function needed to write to the VxWorks target */
+IMAQ_FUNC int Priv_SetWriteFileAllowed(UINT32 enable);
+
+/**
+@brief Possible image sizes that you can set on the camera.
+*/
+enum ImageResolution { k640x480, k320x240, k160x120 };
+
+/**
+@brief Possible rotation values that you can set on the camera.
+*/
+enum ImageRotation { ROT_0 = 0, ROT_180 = 180 };
+
+
+
+int StartCameraTask();
+
+extern "C" {
+/* Image Acquisition functions */
+/* obtains an image from the camera server */
+int GetImage(Image* cameraImage, double *timestamp);
+int GetImageBlocking(Image* cameraImage, double *timestamp, double lastImageTimestamp);
+/* obtains raw image string to send to PC */
+int GetImageData(char** imageData, int* numBytes, double* currentImageTimestamp);
+int GetImageDataBlocking(char** imageData, int* numBytes, double* timestamp, double lastImageTimestamp);
+
+/* start the camera server */
+void StartImageAcquisition();
+void StopImageAcquisition();
+void StartImageSignal(int taskId);
+
+/* status & metrics */
+int frcCameraInitialized();
+int GetCameraMetric(FrcvCameraMetric metric);
+
+/* camera configuration */
+int ConfigureCamera(char *configString);
+int GetCameraSetting(char *configString, char *cameraResponse);
+int GetImageSetting(char *configString, char *cameraResponse);
+
+/* camera task control */
+
+int StartCameraTask(int frames, int compression, ImageResolution resolution, ImageRotation rotation);
+int StopCameraTask();
+}
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Vision2009/BaeUtilities.cpp b/aos/externals/WPILib/WPILib/Vision2009/BaeUtilities.cpp
new file mode 100644
index 0000000..6515893
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision2009/BaeUtilities.cpp
@@ -0,0 +1,400 @@
+/********************************************************************************
+* Project : FIRST Motor Controller
+* File Name : BaeUtilities.cpp
+* Contributors : JDG, ELF, EMF
+* Creation Date : July 20, 2008
+* Revision History : Source code & revision history maintained at sourceforge.WPI.edu
+* File Description : Open source utility extensions for FIRST Vision API.
+*/
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#include <stdio.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <unistd.h>
+#include <string.h>
+#include <math.h>
+#include <stdioLib.h>
+
+#include "BaeUtilities.h"
+#include "Servo.h"
+#include "Timer.h"
+
+/**
+ * Utility functions
+ */
+
+/**
+ * debug output flag options:
+ * DEBUG_OFF, DEBUG_MOSTLY_OFF, DEBUG_SCREEN_ONLY, DEBUG_FILE_ONLY, DEBUG_SCREEN_AND_FILE
+ */
+static DebugOutputType dprintfFlag = DEBUG_OFF;
+
+/**
+ * Set the debug flag to print to screen, file on cRIO, both or neither
+ * @param tempString The format string.
+ */
+void SetDebugFlag ( DebugOutputType flag )
+{ dprintfFlag = flag; }
+
+/**
+ * Debug print to a file and/or a terminal window.
+ * Call like you would call printf.
+ * Set functionName in the function if you want the correct function name to print out.
+ * The file line number will also be printed.
+ * @param tempString The format string.
+ */
+void dprintf ( char * tempString, ... ) /* Variable argument list */
+{
+ va_list args; /* Input argument list */
+ int line_number; /* Line number passed in argument */
+ int type;
+ char *functionName; /* Format passed in argument */
+ char *fmt; /* Format passed in argument */
+ char text[512]; /* Text string */
+ char outtext[512]; /* Text string */
+ FILE *outfile_fd; /* Output file pointer */
+ char filepath[128]; /* Text string */
+ int fatalFlag=0;
+ char *filename;
+ int index;
+ int tempStringLen;
+
+ if (dprintfFlag == DEBUG_OFF) { return; }
+
+ va_start (args, tempString);
+
+ tempStringLen = strlen(tempString);
+ filename = tempString;
+ for (index=0;index<tempStringLen;index++){
+ if (tempString[index] == ' ') {
+ printf( "ERROR in dprintf: malformed calling sequence (%s)\n",tempString);return;
+ }
+ if (tempString[index] == '\\' || tempString[index] == '/')
+ filename = tempString + index + 1;
+ }
+
+ /* Extract function name */
+ functionName = va_arg (args, char *);
+
+ /* Extract line number from argument list */
+ line_number = va_arg (args, int);
+
+ /* Extract information type from argument list */
+ type = va_arg (args, int);
+
+ /* Extract format from argument list */
+ fmt = va_arg (args, char *);
+
+ vsprintf (text, fmt, args);
+
+ va_end (args);
+
+ /* Format output statement */
+ switch (type)
+ {
+ case DEBUG_TYPE:
+ sprintf (outtext, "[%s:%s@%04d] DEBUG %s\n",
+ filename, functionName, line_number, text);
+ break;
+ case INFO_TYPE:
+ sprintf (outtext, "[%s:%s@%04d] INFO %s\n",
+ filename, functionName, line_number, text);
+ break;
+ case ERROR_TYPE:
+ sprintf (outtext, "[%s:%s@%04d] ERROR %s\n",
+ filename, functionName, line_number, text);
+ break;
+ case CRITICAL_TYPE:
+ sprintf (outtext, "[%s:%s@%04d] CRITICAL %s\n",
+ filename, functionName, line_number, text);
+ break;
+ case FATAL_TYPE:
+ fatalFlag = 1;
+ sprintf (outtext, "[%s:%s@%04d] FATAL %s\n",
+ filename, functionName, line_number, text);
+ break;
+ default:
+ printf( "ERROR in dprintf: malformed calling sequence\n");
+ return;
+ break;
+ }
+
+ sprintf (filepath, "%s.debug", filename);
+
+ /* Write output statement */
+ switch (dprintfFlag)
+ {
+ default:
+ case DEBUG_OFF:
+ break;
+ case DEBUG_MOSTLY_OFF:
+ if (fatalFlag) {
+ if ((outfile_fd = fopen (filepath, "a+")) != NULL) {
+ fwrite (outtext, sizeof (char), strlen (outtext), outfile_fd);
+ fclose (outfile_fd);
+ }
+ }
+ break;
+ case DEBUG_SCREEN_ONLY:
+ printf ("%s", outtext);
+ break;
+ case DEBUG_FILE_ONLY:
+ if ((outfile_fd = fopen (filepath, "a+")) != NULL) {
+ fwrite (outtext, sizeof (char), strlen (outtext), outfile_fd);
+ fclose (outfile_fd);
+ }
+ break;
+ case DEBUG_SCREEN_AND_FILE: // BOTH
+ printf ("%s", outtext);
+ if ((outfile_fd = fopen (filepath, "a+")) != NULL) {
+ fwrite (outtext, sizeof (char), strlen (outtext), outfile_fd);
+ fclose (outfile_fd);
+ }
+ break;
+ }
+}
+
+/**
+ * @brief Normalizes a value in a range, used for drive input
+ * @param position The position in the range, starting at 0
+ * @param range The size of the range that position is in
+ * @return The normalized position from -1 to +1
+ */
+double RangeToNormalized(double position, int range){
+ return(((position*2.0)/(double)range)-1.0);
+}
+
+/**
+ * @brief Convert a normalized value to the corresponding value in a range.
+ * This is used to convert normalized values to the servo command range.
+ * @param normalizedValue The normalized value (in the -1 to +1 range)
+ * @param minRange The minimum of the range (0 is default)
+ * @param maxRange The maximum of the range (1 is default)
+ * @return The value in the range corresponding to the input normalized value
+ */
+float NormalizeToRange(float normalizedValue, float minRange, float maxRange) {
+ float range = maxRange-minRange;
+ float temp = (float)((normalizedValue / 2.0)+ 0.5)*range;
+ return (temp + minRange);
+}
+float NormalizeToRange(float normalizedValue) {
+ return (float)((normalizedValue / 2.0) + 0.5);
+}
+
+/**
+ * @brief Displays an activity indicator to console.
+ * Call this function like you would call printf.
+ * @param fmt The format string
+*/
+void ShowActivity (char *fmt, ...)
+{
+ static char activity_indication_string[] = "|/-\\";
+ static int ai = 3;
+ va_list args;
+ char text[1024];
+
+ va_start (args, fmt);
+
+ vsprintf (text, fmt, args);
+
+ ai = ai == 3 ? 0 : ai + 1;
+
+ printf ("%c %s \r", activity_indication_string[ai], text);
+ fflush (stdout);
+
+ va_end (args);
+}
+
+#define PI 3.14159265358979
+/**
+ * @brief Calculate sine wave increments (-1.0 to 1.0).
+ * The first time this is called, it sets up the time increment. Subsequent calls
+ * will give values along the sine wave depending on current time. If the wave is
+ * stopped and restarted, it must be reinitialized with a new "first call".
+ *
+ * @param period length of time to complete a complete wave
+ * @param sinStart Where to start the sine wave (0.0 = 2 pi, pi/2 = 1.0, etc.)
+ */
+double SinPosition (double *period, double sinStart)
+{
+ double rtnVal;
+ static double sinePeriod=0.0;
+ static double timestamp;
+ double sinArg;
+
+ //1st call
+ if (period != NULL) {
+ sinePeriod = *period;
+ timestamp = GetTime();
+ return 0.0;
+ }
+
+ //Multiplying by 2*pi to the time difference makes sinePeriod work if it's measured in seconds.
+ //Adding sinStart to the part multiplied by PI, but not by 2, allows it to work as described in the comments.
+ sinArg = PI *((2.0 * (GetTime() - timestamp)) + sinStart) / sinePeriod;
+ rtnVal = sin (sinArg);
+ return (rtnVal);
+}
+
+
+/**
+ * @brief Find the elapsed time since a specified time.
+ * @param startTime The starting time
+ * @return How long it has been since the starting time
+ */
+double ElapsedTime ( double startTime )
+{
+ double realTime = GetTime();
+ return (realTime-startTime);
+}
+
+/**
+ * @brief Initialize pan parameters
+ * @param period The number of seconds to complete one pan
+ */
+void panInit() {
+ double period = 3.0; // number of seconds for one complete pan
+ SinPosition(&period, 0.0); // initial call to set up time
+}
+
+void panInit(double period) {
+ if (period < 0.0) period=3.0;
+ SinPosition(&period, 0.0); // initial call to set up time
+}
+
+/**
+ * @brief Move the horizontal servo back and forth.
+ * @param panServo The servo object to move
+ * @param sinStart The position on the sine wave to begin the pan
+ */
+void panForTarget(Servo *panServo) { panForTarget(panServo, 0.0); }
+
+void panForTarget(Servo *panServo, double sinStart) {
+ float normalizedSinPosition = (float)SinPosition(NULL, sinStart);
+ float newServoPosition = NormalizeToRange(normalizedSinPosition);
+ panServo->Set( newServoPosition );
+ //ShowActivity ("pan x: normalized %f newServoPosition = %f" ,
+ // normalizedSinPosition, newServoPosition );
+}
+
+
+/** @brief Read a file and return non-comment output string
+
+Call the first time with 0 lineNumber to get the number of lines to read
+Then call with each lineNumber to get one camera parameter. There should
+be one property=value entry on each line, i.e. "exposure=auto"
+
+ * @param inputFile filename to read
+ * @param outputString one string
+ * @param lineNumber if 0, return number of lines; else return that line number
+ * @return int number of lines or -1 if error
+ **/
+int processFile(char *inputFile, char *outputString, int lineNumber)
+{
+ FILE *infile;
+ int stringSize = 80; // max size of one line in file
+ char inputStr[stringSize];
+ struct stat fileStatus;
+ int fileSize=0;
+ int lineCount=0;
+
+ if (lineNumber < 0)
+ return (-1);
+
+ if ((infile = fopen (inputFile, "r")) == NULL) {
+ printf ("Fatal error opening file %s\n",inputFile);
+ return (0);
+ }
+ memset (&fileStatus, 0, sizeof(fileStatus));
+ if (!stat(inputFile, &fileStatus)) {
+ if (S_ISREG(fileStatus.st_mode)) {
+ fileSize = fileStatus.st_size;
+ }
+ }
+
+ while (!feof(infile)) {
+ if (fgets (inputStr, stringSize, infile) != NULL) {
+ // Skip empty lines
+ if (emptyString(inputStr))
+ continue;
+ // Skip comment lines
+ if (inputStr[0] == '#' || inputStr[0] == '!')
+ continue;
+
+ lineCount++;
+ if (lineNumber == 0)
+ continue;
+ else
+ {
+ if (lineCount == lineNumber)
+ break;
+ }
+ }
+ }
+
+ // close file
+ fclose (infile);
+ // if number lines requested return the count
+ if (lineNumber == 0)
+ return (lineCount);
+ // check for input out of range
+ if (lineNumber > lineCount)
+ return (-1);
+ // return the line selected
+ if (lineCount) {
+ stripString(inputStr);
+ strcpy(outputString, inputStr);
+ return(lineCount);
+ }
+ else {
+ return(-1);
+ }
+}
+
+/** Ignore empty string
+ * @param string to check if empty
+ **/
+int emptyString(char *string)
+{
+ int i,len;
+
+ if(string == NULL)
+ return(1);
+
+ len = strlen(string);
+ for(i=0; i<len; i++) {
+ // Ignore the following characters
+ if (string[i] == '\n' || string[i] == '\r' ||
+ string[i] == '\t' || string[i] == ' ')
+ continue;
+ return(0);
+ }
+ return(1);
+}
+
+/** Remove special characters from string
+ * @param string to process
+ **/
+void stripString(char *string)
+{
+ int i,j,len;
+
+ if(string == NULL)
+ return;
+
+ len = strlen(string);
+ for(i=0,j=0; i<len; i++) {
+ // Remove the following characters from the string
+ if (string[i] == '\n' || string[i] == '\r' || string[i] == '\"')
+ continue;
+ // Copy anything else
+ string[j++] = string[i];
+ }
+ string[j] = '\0';
+}
+
+
diff --git a/aos/externals/WPILib/WPILib/Vision2009/BaeUtilities.h b/aos/externals/WPILib/WPILib/Vision2009/BaeUtilities.h
new file mode 100644
index 0000000..cd8ac23
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision2009/BaeUtilities.h
@@ -0,0 +1,68 @@
+/********************************************************************************
+* Project : FIRST Motor Controller
+* File Name : BaeUtilities.h
+* Contributors : JDG, ELF
+* Creation Date : August 12, 2008
+* Revision History : Source code & revision history maintained at sourceforge.WPI.edu
+* File Description : Globally defined values for utilities
+*/
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. */
+/* Must be accompanied by the BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __BAEUTILITIES_H__
+#define __BAEUTILITIES_H__
+
+/* Constants */
+#define LOG_DEBUG __FILE__,__FUNCTION__,__LINE__,DEBUG_TYPE
+#define LOG_INFO __FILE__,__FUNCTION__,__LINE__,INFO_TYPE
+#define LOG_ERROR __FILE__,__FUNCTION__,__LINE__,ERROR_TYPE
+#define LOG_CRITICAL __FILE__,__FUNCTION__,__LINE__,CRITICAL_TYPE
+#define LOG_FATAL __FILE__,__FUNCTION__,__LINE__,FATAL_TYPE
+#define LOG_DEBUG __FILE__,__FUNCTION__,__LINE__,DEBUG_TYPE
+
+/* Enumerated Types */
+
+/** debug levels */
+enum dprint_type {DEBUG_TYPE, INFO_TYPE, ERROR_TYPE, CRITICAL_TYPE, FATAL_TYPE};
+
+/** debug output setting */
+typedef enum DebugOutputType_enum {
+ DEBUG_OFF, DEBUG_MOSTLY_OFF, DEBUG_SCREEN_ONLY, DEBUG_FILE_ONLY, DEBUG_SCREEN_AND_FILE
+}DebugOutputType;
+
+/* Enumerated Types */
+
+/* Utility functions */
+
+/* debug */
+void SetDebugFlag ( DebugOutputType flag );
+void dprintf ( char * tempString, ... ); /* Variable argument list */
+
+/* set FRC ranges for drive */
+double RangeToNormalized(double pixel, int range);
+/* change normalized value to any range - used for servo */
+float NormalizeToRange(float normalizedValue, float minRange, float maxRange);
+float NormalizeToRange(float normalizedValue);
+
+/* system utilities */
+void ShowActivity (char *fmt, ...);
+double ElapsedTime (double startTime);
+
+/* servo panning utilities */
+class Servo;
+double SinPosition (double *period, double sinStart);
+void panInit();
+void panInit(double period);
+void panForTarget(Servo *panServo);
+void panForTarget(Servo *panServo, double sinStart);
+
+/* config file read utilities */
+int processFile(char *inputFile, char *outputString, int lineNumber);
+int emptyString(char *string);
+void stripString(char *string);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Vision2009/FrcError.cpp b/aos/externals/WPILib/WPILib/Vision2009/FrcError.cpp
new file mode 100644
index 0000000..a7f0ba1
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision2009/FrcError.cpp
@@ -0,0 +1,1235 @@
+/********************************************************************************
+* Project : FIRST Motor Controller
+* File Name : FrcError.cpp
+* Contributors : JDG, ELF
+* Creation Date : July 20, 2008
+* Revision History : Source code & revision history maintained at sourceforge.WPI.edu
+* File Description : Error handling functionality for C routines
+*/
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "nivision.h"
+#include "FrcError.h"
+
+/**
+ * Get the error code returned from the NI Vision library
+ * @return The last error code.
+ */
+int GetLastVisionError()
+{
+ //int errorCode = imaqGetLastVisionError(); // error code: 0 = no error
+ //char* errorText = GetVisionErrorText(errorCode);
+ //dprintf (LOG_DEBUG, "Error = %i %s ", errorCode, errorText);
+ return imaqGetLastError();
+}
+
+/**
+* Get the error text for an NI Vision error code.
+* Note: imaqGetErrorText() is not supported on real time system, so
+* so relevant strings are hardcoded here - the maintained version is
+* in the LabWindows/CVI help file.
+* @param errorCode The error code to find the text for.
+* @return The error text
+*/
+char* GetVisionErrorText(int errorCode)
+{
+ char* errorText;
+
+ switch (errorCode)
+ {
+ default:
+ { errorText = "UNKNOWN_ERROR";break;}
+ case -1074395138:
+ { errorText = "ERR_OCR_REGION_TOO_SMALL";break;}
+ case -1074395139:
+ { errorText = "ERR_IMAQ_QR_DIMENSION_INVALID";break;}
+ case -1074395140:
+ { errorText = "ERR_OCR_CHAR_REPORT_CORRUPTED";break;}
+ case -1074395141:
+ { errorText = "ERR_OCR_NO_TEXT_FOUND";break;}
+ case -1074395142:
+ { errorText = "ERR_QR_DETECTION_MODELTYPE";break;}
+ case -1074395143:
+ { errorText = "ERR_QR_DETECTION_MODE";break;}
+ case -1074395144:
+ { errorText = "ERR_QR_INVALID_BARCODE";break;}
+ case -1074395145:
+ { errorText = "ERR_QR_INVALID_READ";break;}
+ case -1074395146:
+ { errorText = "ERR_QR_DETECTION_VERSION";break;}
+ case -1074395147:
+ { errorText = "ERR_BARCODE_RSSLIMITED";break;}
+ case -1074395148:
+ { errorText = "ERR_OVERLAY_GROUP_NOT_FOUND";break;}
+ case -1074395149:
+ { errorText = "ERR_DUPLICATE_TRANSFORM_TYPE";break;}
+ case -1074395151:
+ { errorText = "ERR_OCR_CORRECTION_FAILED";break;}
+ case -1074395155:
+ { errorText = "ERR_OCR_ORIENT_DETECT_FAILED";break;}
+ case -1074395156:
+ { errorText = "ERR_OCR_SKEW_DETECT_FAILED";break;}
+ case -1074395158:
+ { errorText = "ERR_OCR_INVALID_CONTRASTMODE";break;}
+ case -1074395159:
+ { errorText = "ERR_OCR_INVALID_TOLERANCE";break;}
+ case -1074395160:
+ { errorText = "ERR_OCR_INVALID_MAXPOINTSIZE";break;}
+ case -1074395161:
+ { errorText = "ERR_OCR_INVALID_CORRECTIONLEVEL";break;}
+ case -1074395162:
+ { errorText = "ERR_OCR_INVALID_CORRECTIONMODE";break;}
+ case -1074395163:
+ { errorText = "ERR_OCR_INVALID_CHARACTERPREFERENCE";break;}
+ case -1074395164:
+ { errorText = "ERR_OCR_ADD_WORD_FAILED";break;}
+ case -1074395165:
+ { errorText = "ERR_OCR_WTS_DIR_NOT_FOUND";break;}
+ case -1074395166:
+ { errorText = "ERR_OCR_BIN_DIR_NOT_FOUND";break;}
+ case -1074395167:
+ { errorText = "ERR_OCR_INVALID_OUTPUTDELIMITER";break;}
+ case -1074395168:
+ { errorText = "ERR_OCR_INVALID_AUTOCORRECTIONMODE";break;}
+ case -1074395169:
+ { errorText = "ERR_OCR_INVALID_RECOGNITIONMODE";break;}
+ case -1074395170:
+ { errorText = "ERR_OCR_INVALID_CHARACTERTYPE";break;}
+ case -1074395171:
+ { errorText = "ERR_OCR_INI_FILE_NOT_FOUND";break;}
+ case -1074395172:
+ { errorText = "ERR_OCR_INVALID_CHARACTERSET";break;}
+ case -1074395173:
+ { errorText = "ERR_OCR_INVALID_LANGUAGE";break;}
+ case -1074395174:
+ { errorText = "ERR_OCR_INVALID_AUTOORIENTMODE";break;}
+ case -1074395175:
+ { errorText = "ERR_OCR_BAD_USER_DICTIONARY";break;}
+ case -1074395178:
+ { errorText = "ERR_OCR_RECOGNITION_FAILED";break;}
+ case -1074395179:
+ { errorText = "ERR_OCR_PREPROCESSING_FAILED";break;}
+ case -1074395200:
+ { errorText = "ERR_OCR_INVALID_PARAMETER";break;}
+ case -1074395201:
+ { errorText = "ERR_OCR_LOAD_LIBRARY";break;}
+ case -1074395203:
+ { errorText = "ERR_OCR_LIB_INIT";break;}
+ case -1074395210:
+ { errorText = "ERR_OCR_CANNOT_MATCH_TEXT_TEMPLATE";break;}
+ case -1074395211:
+ { errorText = "ERR_OCR_BAD_TEXT_TEMPLATE";break;}
+ case -1074395212:
+ { errorText = "ERR_OCR_TEMPLATE_WRONG_SIZE";break;}
+ case -1074395233:
+ { errorText = "ERR_TEMPLATE_IMAGE_TOO_LARGE";break;}
+ case -1074395234:
+ { errorText = "ERR_TEMPLATE_IMAGE_TOO_SMALL";break;}
+ case -1074395235:
+ { errorText = "ERR_TEMPLATE_IMAGE_CONTRAST_TOO_LOW";break;}
+ case -1074395237:
+ { errorText = "ERR_TEMPLATE_DESCRIPTOR_SHIFT_1";break;}
+ case -1074395238:
+ { errorText = "ERR_TEMPLATE_DESCRIPTOR_NOSHIFT";break;}
+ case -1074395239:
+ { errorText = "ERR_TEMPLATE_DESCRIPTOR_SHIFT";break;}
+ case -1074395240:
+ { errorText = "ERR_TEMPLATE_DESCRIPTOR_ROTATION_1";break;}
+ case -1074395241:
+ { errorText = "ERR_TEMPLATE_DESCRIPTOR_NOROTATION";break;}
+ case -1074395242:
+ { errorText = "ERR_TEMPLATE_DESCRIPTOR_ROTATION";break;}
+ case -1074395243:
+ { errorText = "ERR_TEMPLATE_DESCRIPTOR_4";break;}
+ case -1074395244:
+ { errorText = "ERR_TEMPLATE_DESCRIPTOR_3";break;}
+ case -1074395245:
+ { errorText = "ERR_TEMPLATE_DESCRIPTOR_2";break;}
+ case -1074395246:
+ { errorText = "ERR_TEMPLATE_DESCRIPTOR_1";break;}
+ case -1074395247:
+ { errorText = "ERR_TEMPLATE_DESCRIPTOR";break;}
+ case -1074395248:
+ { errorText = "ERR_TOO_MANY_ROTATION_ANGLE_RANGES";break;}
+ case -1074395249:
+ { errorText = "ERR_ROTATION_ANGLE_RANGE_TOO_LARGE";break;}
+ case -1074395250:
+ { errorText = "ERR_MATCH_SETUP_DATA";break;}
+ case -1074395251:
+ { errorText = "ERR_INVALID_MATCH_MODE";break;}
+ case -1074395252:
+ { errorText = "ERR_LEARN_SETUP_DATA";break;}
+ case -1074395253:
+ { errorText = "ERR_INVALID_LEARN_MODE";break;}
+ case -1074395256:
+ { errorText = "ERR_EVEN_WINDOW_SIZE";break;}
+ case -1074395257:
+ { errorText = "ERR_INVALID_EDGE_DIR";break;}
+ case -1074395258:
+ { errorText = "ERR_BAD_FILTER_WIDTH";break;}
+ case -1074395260:
+ { errorText = "ERR_HEAP_TRASHED";break;}
+ case -1074395261:
+ { errorText = "ERR_GIP_RANGE";break;}
+ case -1074395262:
+ { errorText = "ERR_LCD_BAD_MATCH";break;}
+ case -1074395263:
+ { errorText = "ERR_LCD_NO_SEGMENTS";break;}
+ case -1074395265:
+ { errorText = "ERR_BARCODE";break;}
+ case -1074395267:
+ { errorText = "ERR_COMPLEX_ROOT";break;}
+ case -1074395268:
+ { errorText = "ERR_LINEAR_COEFF";break;}
+ case -1074395269:
+ { errorText = "ERR_NULL_POINTER";break;}
+ case -1074395270:
+ { errorText = "ERR_DIV_BY_ZERO";break;}
+ case -1074395275:
+ { errorText = "ERR_INVALID_BROWSER_IMAGE";break;}
+ case -1074395276:
+ { errorText = "ERR_LINES_PARALLEL";break;}
+ case -1074395277:
+ { errorText = "ERR_BARCODE_CHECKSUM";break;}
+ case -1074395278:
+ { errorText = "ERR_LCD_NOT_NUMERIC";break;}
+ case -1074395279:
+ { errorText = "ERR_ROI_NOT_POLYGON";break;}
+ case -1074395280:
+ { errorText = "ERR_ROI_NOT_RECT";break;}
+ case -1074395281:
+ { errorText = "ERR_IMAGE_SMALLER_THAN_BORDER";break;}
+ case -1074395282:
+ { errorText = "ERR_CANT_DRAW_INTO_VIEWER";break;}
+ case -1074395283:
+ { errorText = "ERR_INVALID_RAKE_DIRECTION";break;}
+ case -1074395284:
+ { errorText = "ERR_INVALID_EDGE_PROCESS";break;}
+ case -1074395285:
+ { errorText = "ERR_INVALID_SPOKE_DIRECTION";break;}
+ case -1074395286:
+ { errorText = "ERR_INVALID_CONCENTRIC_RAKE_DIRECTION";break;}
+ case -1074395287:
+ { errorText = "ERR_INVALID_LINE";break;}
+ case -1074395290:
+ { errorText = "ERR_SHAPEMATCH_BADTEMPLATE";break;}
+ case -1074395291:
+ { errorText = "ERR_SHAPEMATCH_BADIMAGEDATA";break;}
+ case -1074395292:
+ { errorText = "ERR_POINTS_ARE_COLLINEAR";break;}
+ case -1074395293:
+ { errorText = "ERR_CONTOURID_NOT_FOUND";break;}
+ case -1074395294:
+ { errorText = "ERR_CONTOUR_INDEX_OUT_OF_RANGE";break;}
+ case -1074395295:
+ { errorText = "ERR_INVALID_INTERPOLATIONMETHOD_INTERPOLATEPOINTS";break;}
+ case -1074395296:
+ { errorText = "ERR_INVALID_BARCODETYPE";break;}
+ case -1074395297:
+ { errorText = "ERR_INVALID_PARTICLEINFOMODE";break;}
+ case -1074395298:
+ { errorText = "ERR_COMPLEXPLANE_NOT_REAL_OR_IMAGINARY";break;}
+ case -1074395299:
+ { errorText = "ERR_INVALID_COMPLEXPLANE";break;}
+ case -1074395300:
+ { errorText = "ERR_INVALID_METERARCMODE";break;}
+ case -1074395301:
+ { errorText = "ERR_ROI_NOT_2_LINES";break;}
+ case -1074395302:
+ { errorText = "ERR_INVALID_THRESHOLDMETHOD";break;}
+ case -1074395303:
+ { errorText = "ERR_INVALID_NUM_OF_CLASSES";break;}
+ case -1074395304:
+ { errorText = "ERR_INVALID_MATHTRANSFORMMETHOD";break;}
+ case -1074395305:
+ { errorText = "ERR_INVALID_REFERENCEMODE";break;}
+ case -1074395306:
+ { errorText = "ERR_INVALID_TOOL";break;}
+ case -1074395307:
+ { errorText = "ERR_PRECISION_NOT_GTR_THAN_0";break;}
+ case -1074395308:
+ { errorText = "ERR_INVALID_COLORSENSITIVITY";break;}
+ case -1074395309:
+ { errorText = "ERR_INVALID_WINDOW_THREAD_POLICY";break;}
+ case -1074395310:
+ { errorText = "ERR_INVALID_PALETTE_TYPE";break;}
+ case -1074395311:
+ { errorText = "ERR_INVALID_COLOR_SPECTRUM";break;}
+ case -1074395312:
+ { errorText = "ERR_LCD_CALIBRATE";break;}
+ case -1074395313:
+ { errorText = "ERR_WRITE_FILE_NOT_SUPPORTED";break;}
+ case -1074395316:
+ { errorText = "ERR_INVALID_KERNEL_CODE";break;}
+ case -1074395317:
+ { errorText = "ERR_UNDEF_POINT";break;}
+ case -1074395318:
+ { errorText = "ERR_INSF_POINTS";break;}
+ case -1074395319:
+ { errorText = "ERR_INVALID_SUBPIX_TYPE";break;}
+ case -1074395320:
+ { errorText = "ERR_TEMPLATE_EMPTY";break;}
+ case -1074395321:
+ { errorText = "ERR_INVALID_MORPHOLOGYMETHOD";break;}
+ case -1074395322:
+ { errorText = "ERR_INVALID_TEXTALIGNMENT";break;}
+ case -1074395323:
+ { errorText = "ERR_INVALID_FONTCOLOR";break;}
+ case -1074395324:
+ { errorText = "ERR_INVALID_SHAPEMODE";break;}
+ case -1074395325:
+ { errorText = "ERR_INVALID_DRAWMODE";break;}
+ case -1074395326:
+ { errorText = "ERR_INVALID_DRAWMODE_FOR_LINE";break;}
+ case -1074395327:
+ { errorText = "ERR_INVALID_SCALINGMODE";break;}
+ case -1074395328:
+ { errorText = "ERR_INVALID_INTERPOLATIONMETHOD";break;}
+ case -1074395329:
+ { errorText = "ERR_INVALID_OUTLINEMETHOD";break;}
+ case -1074395330:
+ { errorText = "ERR_INVALID_BORDER_SIZE";break;}
+ case -1074395331:
+ { errorText = "ERR_INVALID_BORDERMETHOD";break;}
+ case -1074395332:
+ { errorText = "ERR_INVALID_COMPAREFUNCTION";break;}
+ case -1074395333:
+ { errorText = "ERR_INVALID_VERTICAL_TEXT_ALIGNMENT";break;}
+ case -1074395334:
+ { errorText = "ERR_INVALID_CONVERSIONSTYLE";break;}
+ case -1074395335:
+ { errorText = "ERR_DISPATCH_STATUS_CONFLICT";break;}
+ case -1074395336:
+ { errorText = "ERR_UNKNOWN_ALGORITHM";break;}
+ case -1074395340:
+ { errorText = "ERR_INVALID_SIZETYPE";break;}
+ case -1074395343:
+ { errorText = "ERR_FILE_FILENAME_NULL";break;}
+ case -1074395345:
+ { errorText = "ERR_INVALID_FLIPAXIS";break;}
+ case -1074395346:
+ { errorText = "ERR_INVALID_INTERPOLATIONMETHOD_FOR_ROTATE";break;}
+ case -1074395347:
+ { errorText = "ERR_INVALID_3DDIRECTION";break;}
+ case -1074395348:
+ { errorText = "ERR_INVALID_3DPLANE";break;}
+ case -1074395349:
+ { errorText = "ERR_INVALID_SKELETONMETHOD";break;}
+ case -1074395350:
+ { errorText = "ERR_INVALID_VISION_INFO";break;}
+ case -1074395351:
+ { errorText = "ERR_INVALID_RECT";break;}
+ case -1074395352:
+ { errorText = "ERR_INVALID_FEATURE_MODE";break;}
+ case -1074395353:
+ { errorText = "ERR_INVALID_SEARCH_STRATEGY";break;}
+ case -1074395354:
+ { errorText = "ERR_INVALID_COLOR_WEIGHT";break;}
+ case -1074395355:
+ { errorText = "ERR_INVALID_NUM_MATCHES_REQUESTED";break;}
+ case -1074395356:
+ { errorText = "ERR_INVALID_MIN_MATCH_SCORE";break;}
+ case -1074395357:
+ { errorText = "ERR_INVALID_COLOR_IGNORE_MODE";break;}
+ case -1074395360:
+ { errorText = "ERR_COMPLEX_PLANE";break;}
+ case -1074395361:
+ { errorText = "ERR_INVALID_STEEPNESS";break;}
+ case -1074395362:
+ { errorText = "ERR_INVALID_WIDTH";break;}
+ case -1074395363:
+ { errorText = "ERR_INVALID_SUBSAMPLING_RATIO";break;}
+ case -1074395364:
+ { errorText = "ERR_IGNORE_COLOR_SPECTRUM_SET";break;}
+ case -1074395365:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSPECTRUM";break;}
+ case -1074395366:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSHAPE";break;}
+ case -1074395367:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_5";break;}
+ case -1074395368:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_4";break;}
+ case -1074395369:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_3";break;}
+ case -1074395370:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_2";break;}
+ case -1074395371:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_1";break;}
+ case -1074395372:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_NOROTATION";break;}
+ case -1074395373:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION";break;}
+ case -1074395374:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT_2";break;}
+ case -1074395375:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT_1";break;}
+ case -1074395376:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSHIFT";break;}
+ case -1074395377:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT";break;}
+ case -1074395378:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_6";break;}
+ case -1074395379:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_5";break;}
+ case -1074395380:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_4";break;}
+ case -1074395381:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_3";break;}
+ case -1074395382:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_2";break;}
+ case -1074395383:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_1";break;}
+ case -1074395384:
+ { errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR";break;}
+ case -1074395385:
+ { errorText = "ERR_COLOR_ROTATION_REQUIRES_SHAPE_FEATURE";break;}
+ case -1074395386:
+ { errorText = "ERR_COLOR_MATCH_SETUP_DATA_SHAPE";break;}
+ case -1074395387:
+ { errorText = "ERR_COLOR_MATCH_SETUP_DATA";break;}
+ case -1074395388:
+ { errorText = "ERR_COLOR_LEARN_SETUP_DATA_SHAPE";break;}
+ case -1074395389:
+ { errorText = "ERR_COLOR_LEARN_SETUP_DATA";break;}
+ case -1074395390:
+ { errorText = "ERR_COLOR_TEMPLATE_IMAGE_LUMINANCE_CONTRAST_TOO_LOW";break;}
+ case -1074395391:
+ { errorText = "ERR_COLOR_TEMPLATE_IMAGE_HUE_CONTRAST_TOO_LOW";break;}
+ case -1074395392:
+ { errorText = "ERR_COLOR_TEMPLATE_IMAGE_TOO_LARGE";break;}
+ case -1074395393:
+ { errorText = "ERR_COLOR_TEMPLATE_IMAGE_TOO_SMALL";break;}
+ case -1074395394:
+ { errorText = "ERR_COLOR_SPECTRUM_MASK";break;}
+ case -1074395395:
+ { errorText = "ERR_COLOR_IMAGE_REQUIRED";break;}
+ case -1074395397:
+ { errorText = "ERR_COMPLEX_IMAGE_REQUIRED";break;}
+ case -1074395399:
+ { errorText = "ERR_MULTICORE_INVALID_ARGUMENT";break;}
+ case -1074395400:
+ { errorText = "ERR_MULTICORE_OPERATION";break;}
+ case -1074395401:
+ { errorText = "ERR_INVALID_MATCHFACTOR";break;}
+ case -1074395402:
+ { errorText = "ERR_INVALID_MAXPOINTS";break;}
+ case -1074395403:
+ { errorText = "ERR_EXTRAINFO_VERSION";break;}
+ case -1074395404:
+ { errorText = "ERR_INVALID_INTERPOLATIONMETHOD_FOR_UNWRAP";break;}
+ case -1074395405:
+ { errorText = "ERR_INVALID_TEXTORIENTATION";break;}
+ case -1074395406:
+ { errorText = "ERR_COORDSYS_NOT_FOUND";break;}
+ case -1074395407:
+ { errorText = "ERR_INVALID_CONTRAST";break;}
+ case -1074395408:
+ { errorText = "ERR_INVALID_DETECTION_MODE";break;}
+ case -1074395409:
+ { errorText = "ERR_INVALID_SUBPIXEL_DIVISIONS";break;}
+ case -1074395410:
+ { errorText = "ERR_INVALID_ICONS_PER_LINE";break;}
+ case -1074395549:
+ { errorText = "ERR_NIOCR_INVALID_NUMBER_OF_OBJECTS_TO_VERIFY";break;}
+ case -1074395550:
+ { errorText = "ERR_NIOCR_INVALID_CHARACTER_VALUE";break;}
+ case -1074395551:
+ { errorText = "ERR_NIOCR_RENAME_REFCHAR";break;}
+ case -1074395552:
+ { errorText = "ERR_NIOCR_NOT_A_VALID_CHARACTER_SET";break;}
+ case -1074395553:
+ { errorText = "ERR_NIOCR_INVALID_MIN_BOUNDING_RECT_HEIGHT";break;}
+ case -1074395554:
+ { errorText = "ERR_NIOCR_INVALID_READ_RESOLUTION";break;}
+ case -1074395555:
+ { errorText = "ERR_NIOCR_INVALID_SPACING_RANGE";break;}
+ case -1074395556:
+ { errorText = "ERR_NIOCR_INVALID_BOUNDING_RECT_HEIGHT_RANGE";break;}
+ case -1074395557:
+ { errorText = "ERR_NIOCR_INVALID_BOUNDING_RECT_WIDTH_RANGE";break;}
+ case -1074395558:
+ { errorText = "ERR_NIOCR_INVALID_CHARACTER_SIZE_RANGE";break;}
+ case -1074395559:
+ { errorText = "ERR_NIOCR_INVALID_READ_OPTION";break;}
+ case -1074395560:
+ { errorText = "ERR_NIOCR_INVALID_OBJECT_INDEX";break;}
+ case -1074395561:
+ { errorText = "ERR_NIOCR_INVALID_NUMBER_OF_CHARACTERS";break;}
+ case -1074395562:
+ { errorText = "ERR_NIOCR_BOOLEAN_VALUE_FOR_STRING_ATTRIBUTE";break;}
+ case -1074395563:
+ { errorText = "ERR_NIOCR_UNLICENSED";break;}
+ case -1074395564:
+ { errorText = "ERR_NIOCR_INVALID_PREDEFINED_CHARACTER";break;}
+ case -1074395565:
+ { errorText = "ERR_NIOCR_MUST_BE_SINGLE_CHARACTER";break;}
+ case -1074395566:
+ { errorText = "ERR_NIOCR_BOOLEAN_VALUE_FOR_INTEGER_ATTRIBUTE";break;}
+ case -1074395567:
+ { errorText = "ERR_NIOCR_STRING_VALUE_FOR_BOOLEAN_ATTRIBUTE";break;}
+ case -1074395568:
+ { errorText = "ERR_NIOCR_STRING_VALUE_FOR_INTEGER_ATTRIBUTE";break;}
+ case -1074395569:
+ { errorText = "ERR_NIOCR_INVALID_ATTRIBUTE";break;}
+ case -1074395570:
+ { errorText = "ERR_NIOCR_INTEGER_VALUE_FOR_BOOLEAN_ATTRIBUTE";break;}
+ case -1074395571:
+ { errorText = "ERR_NIOCR_GET_ONLY_ATTRIBUTE";break;}
+ case -1074395572:
+ { errorText = "ERR_NIOCR_INTEGER_VALUE_FOR_STRING_ATTRIBUTE";break;}
+ case -1074395573:
+ { errorText = "ERR_NIOCR_INVALID_CHARACTER_SET_FILE_VERSION";break;}
+ case -1074395574:
+ { errorText = "ERR_NIOCR_CHARACTER_SET_DESCRIPTION_TOO_LONG";break;}
+ case -1074395575:
+ { errorText = "ERR_NIOCR_INVALID_NUMBER_OF_EROSIONS";break;}
+ case -1074395576:
+ { errorText = "ERR_NIOCR_CHARACTER_VALUE_TOO_LONG";break;}
+ case -1074395577:
+ { errorText = "ERR_NIOCR_CHARACTER_VALUE_CANNOT_BE_EMPTYSTRING";break;}
+ case -1074395578:
+ { errorText = "ERR_NIOCR_INVALID_CHARACTER_SET_FILE";break;}
+ case -1074395579:
+ { errorText = "ERR_NIOCR_INVALID_ASPECT_RATIO";break;}
+ case -1074395580:
+ { errorText = "ERR_NIOCR_INVALID_MIN_BOUNDING_RECT_WIDTH";break;}
+ case -1074395581:
+ { errorText = "ERR_NIOCR_INVALID_MAX_VERT_ELEMENT_SPACING";break;}
+ case -1074395582:
+ { errorText = "ERR_NIOCR_INVALID_MAX_HORIZ_ELEMENT_SPACING";break;}
+ case -1074395583:
+ { errorText = "ERR_NIOCR_INVALID_MIN_CHAR_SPACING";break;}
+ case -1074395584:
+ { errorText = "ERR_NIOCR_INVALID_THRESHOLD_LIMITS";break;}
+ case -1074395585:
+ { errorText = "ERR_NIOCR_INVALID_UPPER_THRESHOLD_LIMIT";break;}
+ case -1074395586:
+ { errorText = "ERR_NIOCR_INVALID_LOWER_THRESHOLD_LIMIT";break;}
+ case -1074395587:
+ { errorText = "ERR_NIOCR_INVALID_THRESHOLD_RANGE";break;}
+ case -1074395588:
+ { errorText = "ERR_NIOCR_INVALID_HIGH_THRESHOLD_VALUE";break;}
+ case -1074395589:
+ { errorText = "ERR_NIOCR_INVALID_LOW_THRESHOLD_VALUE";break;}
+ case -1074395590:
+ { errorText = "ERR_NIOCR_INVALID_NUMBER_OF_VALID_CHARACTER_POSITIONS";break;}
+ case -1074395591:
+ { errorText = "ERR_NIOCR_INVALID_CHARACTER_INDEX";break;}
+ case -1074395592:
+ { errorText = "ERR_NIOCR_INVALID_READ_STRATEGY";break;}
+ case -1074395593:
+ { errorText = "ERR_NIOCR_INVALID_NUMBER_OF_BLOCKS";break;}
+ case -1074395594:
+ { errorText = "ERR_NIOCR_INVALID_SUBSTITUTION_CHARACTER";break;}
+ case -1074395595:
+ { errorText = "ERR_NIOCR_INVALID_THRESHOLD_MODE";break;}
+ case -1074395596:
+ { errorText = "ERR_NIOCR_INVALID_CHARACTER_SIZE";break;}
+ case -1074395597:
+ { errorText = "ERR_NIOCR_NOT_A_VALID_SESSION";break;}
+ case -1074395598:
+ { errorText = "ERR_NIOCR_INVALID_ACCEPTANCE_LEVEL";break;}
+ case -1074395600:
+ { errorText = "ERR_INFO_NOT_FOUND";break;}
+ case -1074395601:
+ { errorText = "ERR_INVALID_EDGE_THRESHOLD";break;}
+ case -1074395602:
+ { errorText = "ERR_INVALID_MINIMUM_CURVE_LENGTH";break;}
+ case -1074395603:
+ { errorText = "ERR_INVALID_ROW_STEP";break;}
+ case -1074395604:
+ { errorText = "ERR_INVALID_COLUMN_STEP";break;}
+ case -1074395605:
+ { errorText = "ERR_INVALID_MAXIMUM_END_POINT_GAP";break;}
+ case -1074395606:
+ { errorText = "ERR_INVALID_MINIMUM_FEATURES_TO_MATCH";break;}
+ case -1074395607:
+ { errorText = "ERR_INVALID_MAXIMUM_FEATURES_PER_MATCH";break;}
+ case -1074395608:
+ { errorText = "ERR_INVALID_SUBPIXEL_ITERATIONS";break;}
+ case -1074395609:
+ { errorText = "ERR_INVALID_SUBPIXEL_TOLERANCE";break;}
+ case -1074395610:
+ { errorText = "ERR_INVALID_INITIAL_MATCH_LIST_LENGTH";break;}
+ case -1074395611:
+ { errorText = "ERR_INVALID_MINIMUM_RECTANGLE_DIMENSION";break;}
+ case -1074395612:
+ { errorText = "ERR_INVALID_MINIMUM_FEATURE_RADIUS";break;}
+ case -1074395613:
+ { errorText = "ERR_INVALID_MINIMUM_FEATURE_LENGTH";break;}
+ case -1074395614:
+ { errorText = "ERR_INVALID_MINIMUM_FEATURE_ASPECT_RATIO";break;}
+ case -1074395615:
+ { errorText = "ERR_INVALID_MINIMUM_FEATURE_STRENGTH";break;}
+ case -1074395616:
+ { errorText = "ERR_INVALID_EDGE_FILTER_SIZE";break;}
+ case -1074395617:
+ { errorText = "ERR_INVALID_NUMBER_OF_FEATURES_RANGE";break;}
+ case -1074395618:
+ { errorText = "ERR_TOO_MANY_SCALE_RANGES";break;}
+ case -1074395619:
+ { errorText = "ERR_TOO_MANY_OCCLUSION_RANGES";break;}
+ case -1074395620:
+ { errorText = "ERR_INVALID_CURVE_EXTRACTION_MODE";break;}
+ case -1074395621:
+ { errorText = "ERR_INVALID_LEARN_GEOMETRIC_PATTERN_SETUP_DATA";break;}
+ case -1074395622:
+ { errorText = "ERR_INVALID_MATCH_GEOMETRIC_PATTERN_SETUP_DATA";break;}
+ case -1074395623:
+ { errorText = "ERR_INVALID_SCALE_RANGE";break;}
+ case -1074395624:
+ { errorText = "ERR_INVALID_OCCLUSION_RANGE";break;}
+ case -1074395625:
+ { errorText = "ERR_INVALID_MATCH_CONSTRAINT_TYPE";break;}
+ case -1074395626:
+ { errorText = "ERR_NOT_ENOUGH_TEMPLATE_FEATURES";break;}
+ case -1074395627:
+ { errorText = "ERR_NOT_ENOUGH_TEMPLATE_FEATURES_1";break;}
+ case -1074395628:
+ { errorText = "ERR_INVALID_GEOMETRIC_MATCHING_TEMPLATE";break;}
+ case -1074395629:
+ { errorText = "ERR_INVALID_MAXIMUM_PIXEL_DISTANCE_FROM_LINE";break;}
+ case -1074395630:
+ { errorText = "ERR_INVALID_MAXIMUM_FEATURES_LEARNED";break;}
+ case -1074395631:
+ { errorText = "ERR_INVALID_MIN_MATCH_SEPARATION_DISTANCE";break;}
+ case -1074395632:
+ { errorText = "ERR_INVALID_MIN_MATCH_SEPARATION_ANGLE";break;}
+ case -1074395633:
+ { errorText = "ERR_INVALID_MIN_MATCH_SEPARATION_SCALE";break;}
+ case -1074395634:
+ { errorText = "ERR_INVALID_MAX_MATCH_OVERLAP";break;}
+ case -1074395635:
+ { errorText = "ERR_INVALID_SHAPE_DESCRIPTOR";break;}
+ case -1074395636:
+ { errorText = "ERR_DIRECTX_NOT_FOUND";break;}
+ case -1074395637:
+ { errorText = "ERR_HARDWARE_DOESNT_SUPPORT_NONTEARING";break;}
+ case -1074395638:
+ { errorText = "ERR_INVALID_FILL_STYLE";break;}
+ case -1074395639:
+ { errorText = "ERR_INVALID_HATCH_STYLE";break;}
+ case -1074395640:
+ { errorText = "ERR_TOO_MANY_ZONES";break;}
+ case -1074395641:
+ { errorText = "ERR_DUPLICATE_LABEL";break;}
+ case -1074395642:
+ { errorText = "ERR_LABEL_NOT_FOUND";break;}
+ case -1074395643:
+ { errorText = "ERR_INVALID_NUMBER_OF_MATCH_OPTIONS";break;}
+ case -1074395644:
+ { errorText = "ERR_LABEL_TOO_LONG";break;}
+ case -1074395645:
+ { errorText = "ERR_INVALID_NUMBER_OF_LABELS";break;}
+ case -1074395646:
+ { errorText = "ERR_NO_TEMPLATE_TO_LEARN";break;}
+ case -1074395647:
+ { errorText = "ERR_INVALID_MULTIPLE_GEOMETRIC_TEMPLATE";break;}
+ case -1074395648:
+ { errorText = "ERR_TEMPLATE_NOT_LEARNED";break;}
+ case -1074395649:
+ { errorText = "ERR_INVALID_GEOMETRIC_FEATURE_TYPE";break;}
+ case -1074395650:
+ { errorText = "ERR_CURVE_EXTRACTION_MODE_MUST_BE_SAME";break;}
+ case -1074395651:
+ { errorText = "ERR_EDGE_FILTER_SIZE_MUST_BE_SAME";break;}
+ case -1074395652:
+ { errorText = "ERR_OPENING_NEWER_GEOMETRIC_MATCHING_TEMPLATE";break;}
+ case -1074395653:
+ { errorText = "ERR_OPENING_NEWER_MULTIPLE_GEOMETRIC_TEMPLATE";break;}
+ case -1074395654:
+ { errorText = "ERR_GRADING_INFORMATION_NOT_FOUND";break;}
+ case -1074395655:
+ { errorText = "ERR_ENABLE_CALIBRATION_SUPPORT_MUST_BE_SAME";break;}
+ case -1074395656:
+ { errorText = "ERR_SMOOTH_CONTOURS_MUST_BE_SAME";break;}
+ case -1074395700:
+ { errorText = "ERR_REQUIRES_WIN2000_OR_NEWER";break;}
+ case -1074395701:
+ { errorText = "ERR_INVALID_MATRIX_SIZE_RANGE";break;}
+ case -1074395702:
+ { errorText = "ERR_INVALID_LENGTH";break;}
+ case -1074395703:
+ { errorText = "ERR_INVALID_TYPE_OF_FLATTEN";break;}
+ case -1074395704:
+ { errorText = "ERR_INVALID_COMPRESSION_TYPE";break;}
+ case -1074395705:
+ { errorText = "ERR_DATA_CORRUPTED";break;}
+ case -1074395706:
+ { errorText = "ERR_AVI_SESSION_ALREADY_OPEN";break;}
+ case -1074395707:
+ { errorText = "ERR_AVI_WRITE_SESSION_REQUIRED";break;}
+ case -1074395708:
+ { errorText = "ERR_AVI_READ_SESSION_REQUIRED";break;}
+ case -1074395709:
+ { errorText = "ERR_AVI_UNOPENED_SESSION";break;}
+ case -1074395710:
+ { errorText = "ERR_TOO_MANY_PARTICLES";break;}
+ case -1074395711:
+ { errorText = "ERR_NOT_ENOUGH_REGIONS";break;}
+ case -1074395712:
+ { errorText = "ERR_WRONG_REGION_TYPE";break;}
+ case -1074395713:
+ { errorText = "ERR_VALUE_NOT_IN_ENUM";break;}
+ case -1074395714:
+ { errorText = "ERR_INVALID_AXIS_ORIENTATION";break;}
+ case -1074395715:
+ { errorText = "ERR_INVALID_CALIBRATION_UNIT";break;}
+ case -1074395716:
+ { errorText = "ERR_INVALID_SCALING_METHOD";break;}
+ case -1074395717:
+ { errorText = "ERR_INVALID_RANGE";break;}
+ case -1074395718:
+ { errorText = "ERR_LAB_VERSION";break;}
+ case -1074395719:
+ { errorText = "ERR_BAD_ROI_BOX";break;}
+ case -1074395720:
+ { errorText = "ERR_BAD_ROI";break;}
+ case -1074395721:
+ { errorText = "ERR_INVALID_BIT_DEPTH";break;}
+ case -1074395722:
+ { errorText = "ERR_CLASSIFIER_CLASSIFY_IMAGE_WITH_CUSTOM_SESSION";break;}
+ case -1074395723:
+ { errorText = "ERR_CUSTOMDATA_KEY_NOT_FOUND";break;}
+ case -1074395724:
+ { errorText = "ERR_CUSTOMDATA_INVALID_SIZE";break;}
+ case -1074395725:
+ { errorText = "ERR_DATA_VERSION";break;}
+ case -1074395726:
+ { errorText = "ERR_MATCHFACTOR_OBSOLETE";break;}
+ case -1074395727:
+ { errorText = "ERR_UNSUPPORTED_2D_BARCODE_SEARCH_MODE";break;}
+ case -1074395728:
+ { errorText = "ERR_INVALID_2D_BARCODE_SEARCH_MODE";break;}
+ case -1074395754:
+ { errorText = "ERR_TRIG_TIMEOUT";break;}
+ case -1074395756:
+ { errorText = "ERR_DLL_FUNCTION_NOT_FOUND";break;}
+ case -1074395757:
+ { errorText = "ERR_DLL_NOT_FOUND";break;}
+ case -1074395758:
+ { errorText = "ERR_BOARD_NOT_OPEN";break;}
+ case -1074395760:
+ { errorText = "ERR_BOARD_NOT_FOUND";break;}
+ case -1074395762:
+ { errorText = "ERR_INVALID_NIBLACK_DEVIATION_FACTOR";break;}
+ case -1074395763:
+ { errorText = "ERR_INVALID_NORMALIZATION_METHOD";break;}
+ case -1074395766:
+ { errorText = "ERR_DEPRECATED_FUNCTION";break;}
+ case -1074395767:
+ { errorText = "ERR_INVALID_ALIGNMENT";break;}
+ case -1074395768:
+ { errorText = "ERR_INVALID_SCALE";break;}
+ case -1074395769:
+ { errorText = "ERR_INVALID_EDGE_THICKNESS";break;}
+ case -1074395770:
+ { errorText = "ERR_INVALID_INSPECTION_TEMPLATE";break;}
+ case -1074395771:
+ { errorText = "ERR_OPENING_NEWER_INSPECTION_TEMPLATE";break;}
+ case -1074395772:
+ { errorText = "ERR_INVALID_REGISTRATION_METHOD";break;}
+ case -1074395773:
+ { errorText = "ERR_NO_DEST_IMAGE";break;}
+ case -1074395774:
+ { errorText = "ERR_NO_LABEL";break;}
+ case -1074395775:
+ { errorText = "ERR_ROI_HAS_OPEN_CONTOURS";break;}
+ case -1074395776:
+ { errorText = "ERR_INVALID_USE_OF_COMPACT_SESSION_FILE";break;}
+ case -1074395777:
+ { errorText = "ERR_INCOMPATIBLE_CLASSIFIER_TYPES";break;}
+ case -1074395778:
+ { errorText = "ERR_INVALID_KERNEL_SIZE";break;}
+ case -1074395779:
+ { errorText = "ERR_CANNOT_COMPACT_UNTRAINED";break;}
+ case -1074395780:
+ { errorText = "ERR_INVALID_PARTICLE_TYPE";break;}
+ case -1074395781:
+ { errorText = "ERR_CLASSIFIER_INVALID_ENGINE_TYPE";break;}
+ case -1074395782:
+ { errorText = "ERR_DESCRIPTION_TOO_LONG";break;}
+ case -1074395783:
+ { errorText = "ERR_BAD_SAMPLE_INDEX";break;}
+ case -1074395784:
+ { errorText = "ERR_INVALID_LIMITS";break;}
+ case -1074395785:
+ { errorText = "ERR_NO_PARTICLE";break;}
+ case -1074395786:
+ { errorText = "ERR_INVALID_PARTICLE_OPTIONS";break;}
+ case -1074395787:
+ { errorText = "ERR_INVALID_CLASSIFIER_TYPE";break;}
+ case -1074395788:
+ { errorText = "ERR_NO_SAMPLES";break;}
+ case -1074395789:
+ { errorText = "ERR_OPENING_NEWER_CLASSIFIER_SESSION";break;}
+ case -1074395790:
+ { errorText = "ERR_INVALID_DISTANCE_METRIC";break;}
+ case -1074395791:
+ { errorText = "ERR_CLASSIFIER_INVALID_SESSION_TYPE";break;}
+ case -1074395792:
+ { errorText = "ERR_CLASSIFIER_SESSION_NOT_TRAINED";break;}
+ case -1074395793:
+ { errorText = "ERR_INVALID_OPERATION_ON_COMPACT_SESSION_ATTEMPTED";break;}
+ case -1074395794:
+ { errorText = "ERR_K_TOO_HIGH";break;}
+ case -1074395795:
+ { errorText = "ERR_K_TOO_LOW";break;}
+ case -1074395796:
+ { errorText = "ERR_INVALID_KNN_METHOD";break;}
+ case -1074395797:
+ { errorText = "ERR_INVALID_CLASSIFIER_SESSION";break;}
+ case -1074395798:
+ { errorText = "ERR_INVALID_CUSTOM_SAMPLE";break;}
+ case -1074395799:
+ { errorText = "ERR_INTERNAL";break;}
+ case -1074395800:
+ { errorText = "ERR_PROTECTION";break;}
+ case -1074395801:
+ { errorText = "ERR_TOO_MANY_CONTOURS";break;}
+ case -1074395837:
+ { errorText = "ERR_INVALID_COMPRESSION_RATIO";break;}
+ case -1074395840:
+ { errorText = "ERR_BAD_INDEX";break;}
+ case -1074395875:
+ { errorText = "ERR_BARCODE_PHARMACODE";break;}
+ case -1074395876:
+ { errorText = "ERR_UNSUPPORTED_COLOR_MODE";break;}
+ case -1074395877:
+ { errorText = "ERR_COLORMODE_REQUIRES_CHANGECOLORSPACE2";break;}
+ case -1074395878:
+ { errorText = "ERR_PROP_NODE_WRITE_NOT_SUPPORTED";break;}
+ case -1074395879:
+ { errorText = "ERR_BAD_MEASURE";break;}
+ case -1074395880:
+ { errorText = "ERR_PARTICLE";break;}
+ case -1074395920:
+ { errorText = "ERR_NUMBER_CLASS";break;}
+ case -1074395953:
+ { errorText = "ERR_INVALID_WAVELET_TRANSFORM_MODE";break;}
+ case -1074395954:
+ { errorText = "ERR_INVALID_QUANTIZATION_STEP_SIZE";break;}
+ case -1074395955:
+ { errorText = "ERR_INVALID_MAX_WAVELET_TRANSFORM_LEVEL";break;}
+ case -1074395956:
+ { errorText = "ERR_INVALID_QUALITY";break;}
+ case -1074395957:
+ { errorText = "ERR_ARRAY_SIZE_MISMATCH";break;}
+ case -1074395958:
+ { errorText = "ERR_WINDOW_ID";break;}
+ case -1074395959:
+ { errorText = "ERR_CREATE_WINDOW";break;}
+ case -1074395960:
+ { errorText = "ERR_INIT";break;}
+ case -1074395971:
+ { errorText = "ERR_INVALID_OFFSET";break;}
+ case -1074395972:
+ { errorText = "ERR_DIRECTX_ENUMERATE_FILTERS";break;}
+ case -1074395973:
+ { errorText = "ERR_JPEG2000_UNSUPPORTED_MULTIPLE_LAYERS";break;}
+ case -1074395974:
+ { errorText = "ERR_UNSUPPORTED_JPEG2000_COLORSPACE_METHOD";break;}
+ case -1074395975:
+ { errorText = "ERR_AVI_TIMEOUT";break;}
+ case -1074395976:
+ { errorText = "ERR_NUMBER_OF_PALETTE_COLORS";break;}
+ case -1074395977:
+ { errorText = "ERR_AVI_VERSION";break;}
+ case -1074395978:
+ { errorText = "ERR_INVALID_PARTICLE_NUMBER";break;}
+ case -1074395979:
+ { errorText = "ERR_INVALID_PARTICLE_INFO";break;}
+ case -1074395980:
+ { errorText = "ERR_COM_INITIALIZE";break;}
+ case -1074395981:
+ { errorText = "ERR_INSUFFICIENT_BUFFER_SIZE";break;}
+ case -1074395982:
+ { errorText = "ERR_INVALID_FRAMES_PER_SECOND";break;}
+ case -1074395983:
+ { errorText = "ERR_FILE_NO_SPACE";break;}
+ case -1074395984:
+ { errorText = "ERR_FILE_INVALID_DATA_TYPE";break;}
+ case -1074395985:
+ { errorText = "ERR_FILE_OPERATION";break;}
+ case -1074395986:
+ { errorText = "ERR_FILE_FORMAT";break;}
+ case -1074395987:
+ { errorText = "ERR_FILE_EOF";break;}
+ case -1074395988:
+ { errorText = "ERR_FILE_WRITE";break;}
+ case -1074395989:
+ { errorText = "ERR_FILE_READ";break;}
+ case -1074395990:
+ { errorText = "ERR_FILE_GET_INFO";break;}
+ case -1074395991:
+ { errorText = "ERR_FILE_INVALID_TYPE";break;}
+ case -1074395992:
+ { errorText = "ERR_FILE_PERMISSION";break;}
+ case -1074395993:
+ { errorText = "ERR_FILE_IO_ERR";break;}
+ case -1074395994:
+ { errorText = "ERR_FILE_TOO_MANY_OPEN";break;}
+ case -1074395995:
+ { errorText = "ERR_FILE_NOT_FOUND";break;}
+ case -1074395996:
+ { errorText = "ERR_FILE_OPEN";break;}
+ case -1074395997:
+ { errorText = "ERR_FILE_ARGERR";break;}
+ case -1074395998:
+ { errorText = "ERR_FILE_COLOR_TABLE";break;}
+ case -1074395999:
+ { errorText = "ERR_FILE_FILE_TYPE";break;}
+ case -1074396000:
+ { errorText = "ERR_FILE_FILE_HEADER";break;}
+ case -1074396001:
+ { errorText = "ERR_TOO_MANY_AVI_SESSIONS";break;}
+ case -1074396002:
+ { errorText = "ERR_INVALID_LINEGAUGEMETHOD";break;}
+ case -1074396003:
+ { errorText = "ERR_AVI_DATA_EXCEEDS_BUFFER_SIZE";break;}
+ case -1074396004:
+ { errorText = "ERR_DIRECTX_CERTIFICATION_FAILURE";break;}
+ case -1074396005:
+ { errorText = "ERR_INVALID_AVI_SESSION";break;}
+ case -1074396006:
+ { errorText = "ERR_DIRECTX_UNKNOWN_COMPRESSION_FILTER";break;}
+ case -1074396007:
+ { errorText = "ERR_DIRECTX_INCOMPATIBLE_COMPRESSION_FILTER";break;}
+ case -1074396008:
+ { errorText = "ERR_DIRECTX_NO_FILTER";break;}
+ case -1074396009:
+ { errorText = "ERR_DIRECTX";break;}
+ case -1074396010:
+ { errorText = "ERR_INVALID_FRAME_NUMBER";break;}
+ case -1074396011:
+ { errorText = "ERR_RPC_BIND";break;}
+ case -1074396012:
+ { errorText = "ERR_RPC_EXECUTE";break;}
+ case -1074396013:
+ { errorText = "ERR_INVALID_VIDEO_MODE";break;}
+ case -1074396014:
+ { errorText = "ERR_INVALID_VIDEO_BLIT";break;}
+ case -1074396015:
+ { errorText = "ERR_RPC_EXECUTE_IVB";break;}
+ case -1074396016:
+ { errorText = "ERR_NO_VIDEO_DRIVER";break;}
+ case -1074396017:
+ { errorText = "ERR_OPENING_NEWER_AIM_GRADING_DATA";break;}
+ case -1074396018:
+ { errorText = "ERR_INVALID_EDGE_POLARITY_SEARCH_MODE";break;}
+ case -1074396019:
+ { errorText = "ERR_INVALID_THRESHOLD_PERCENTAGE";break;}
+ case -1074396020:
+ { errorText = "ERR_INVALID_GRADING_MODE";break;}
+ case -1074396021:
+ { errorText = "ERR_INVALID_KERNEL_SIZE_FOR_EDGE_DETECTION";break;}
+ case -1074396022:
+ { errorText = "ERR_INVALID_SEARCH_MODE_FOR_STRAIGHT_EDGE";break;}
+ case -1074396023:
+ { errorText = "ERR_INVALID_ANGLE_TOL_FOR_STRAIGHT_EDGE";break;}
+ case -1074396024:
+ { errorText = "ERR_INVALID_MIN_COVERAGE_FOR_STRAIGHT_EDGE";break;}
+ case -1074396025:
+ { errorText = "ERR_INVALID_ANGLE_RANGE_FOR_STRAIGHT_EDGE";break;}
+ case -1074396026:
+ { errorText = "ERR_INVALID_PROCESS_TYPE_FOR_EDGE_DETECTION";break;}
+ case -1074396032:
+ { errorText = "ERR_TEMPLATEDESCRIPTOR_ROTATION_SEARCHSTRATEGY";break;}
+ case -1074396033:
+ { errorText = "ERR_TEMPLATEDESCRIPTOR_LEARNSETUPDATA";break;}
+ case -1074396034:
+ { errorText = "ERR_TEMPLATEIMAGE_EDGEINFO";break;}
+ case -1074396035:
+ { errorText = "ERR_TEMPLATEIMAGE_NOCIRCLE";break;}
+ case -1074396036:
+ { errorText = "ERR_INVALID_SKELETONMODE";break;}
+ case -1074396037:
+ { errorText = "ERR_TIMEOUT";break;}
+ case -1074396038:
+ { errorText = "ERR_FIND_COORDSYS_MORE_THAN_ONE_EDGE";break;}
+ case -1074396039:
+ { errorText = "ERR_IO_ERROR";break;}
+ case -1074396040:
+ { errorText = "ERR_DRIVER";break;}
+ case -1074396041:
+ { errorText = "ERR_INVALID_2D_BARCODE_TYPE";break;}
+ case -1074396042:
+ { errorText = "ERR_INVALID_2D_BARCODE_CONTRAST";break;}
+ case -1074396043:
+ { errorText = "ERR_INVALID_2D_BARCODE_CELL_SHAPE";break;}
+ case -1074396044:
+ { errorText = "ERR_INVALID_2D_BARCODE_SHAPE";break;}
+ case -1074396045:
+ { errorText = "ERR_INVALID_2D_BARCODE_SUBTYPE";break;}
+ case -1074396046:
+ { errorText = "ERR_INVALID_2D_BARCODE_CONTRAST_FOR_ROI";break;}
+ case -1074396047:
+ { errorText = "ERR_INVALID_LINEAR_AVERAGE_MODE";break;}
+ case -1074396048:
+ { errorText = "ERR_INVALID_CELL_SAMPLE_SIZE";break;}
+ case -1074396049:
+ { errorText = "ERR_INVALID_MATRIX_POLARITY";break;}
+ case -1074396050:
+ { errorText = "ERR_INVALID_ECC_TYPE";break;}
+ case -1074396051:
+ { errorText = "ERR_INVALID_CELL_FILTER_MODE";break;}
+ case -1074396052:
+ { errorText = "ERR_INVALID_DEMODULATION_MODE";break;}
+ case -1074396053:
+ { errorText = "ERR_INVALID_BORDER_INTEGRITY";break;}
+ case -1074396054:
+ { errorText = "ERR_INVALID_CELL_FILL_TYPE";break;}
+ case -1074396055:
+ { errorText = "ERR_INVALID_ASPECT_RATIO";break;}
+ case -1074396056:
+ { errorText = "ERR_INVALID_MATRIX_MIRROR_MODE";break;}
+ case -1074396057:
+ { errorText = "ERR_INVALID_SEARCH_VECTOR_WIDTH";break;}
+ case -1074396058:
+ { errorText = "ERR_INVALID_ROTATION_MODE";break;}
+ case -1074396059:
+ { errorText = "ERR_INVALID_MAX_ITERATIONS";break;}
+ case -1074396060:
+ { errorText = "ERR_JPEG2000_LOSSLESS_WITH_FLOATING_POINT";break;}
+ case -1074396061:
+ { errorText = "ERR_INVALID_WINDOW_SIZE";break;}
+ case -1074396062:
+ { errorText = "ERR_INVALID_TOLERANCE";break;}
+ case -1074396063:
+ { errorText = "ERR_EXTERNAL_ALIGNMENT";break;}
+ case -1074396064:
+ { errorText = "ERR_EXTERNAL_NOT_SUPPORTED";break;}
+ case -1074396065:
+ { errorText = "ERR_CANT_RESIZE_EXTERNAL";break;}
+ case -1074396066:
+ { errorText = "ERR_INVALID_POINTSYMBOL";break;}
+ case -1074396067:
+ { errorText = "ERR_IMAGES_NOT_DIFF";break;}
+ case -1074396068:
+ { errorText = "ERR_INVALID_ACTION";break;}
+ case -1074396069:
+ { errorText = "ERR_INVALID_COLOR_MODE";break;}
+ case -1074396070:
+ { errorText = "ERR_INVALID_FUNCTION";break;}
+ case -1074396071:
+ { errorText = "ERR_INVALID_SCAN_DIRECTION";break;}
+ case -1074396072:
+ { errorText = "ERR_INVALID_BORDER";break;}
+ case -1074396073:
+ { errorText = "ERR_MASK_OUTSIDE_IMAGE";break;}
+ case -1074396074:
+ { errorText = "ERR_INCOMP_SIZE";break;}
+ case -1074396075:
+ { errorText = "ERR_COORD_SYS_SECOND_AXIS";break;}
+ case -1074396076:
+ { errorText = "ERR_COORD_SYS_FIRST_AXIS";break;}
+ case -1074396077:
+ { errorText = "ERR_INCOMP_TYPE";break;}
+ case -1074396079:
+ { errorText = "ERR_INVALID_METAFILE_HANDLE";break;}
+ case -1074396080:
+ { errorText = "ERR_INVALID_IMAGE_TYPE";break;}
+ case -1074396081:
+ { errorText = "ERR_BAD_PASSWORD";break;}
+ case -1074396082:
+ { errorText = "ERR_PALETTE_NOT_SUPPORTED";break;}
+ case -1074396083:
+ { errorText = "ERR_ROLLBACK_TIMEOUT";break;}
+ case -1074396084:
+ { errorText = "ERR_ROLLBACK_DELETE_TIMER";break;}
+ case -1074396085:
+ { errorText = "ERR_ROLLBACK_INIT_TIMER";break;}
+ case -1074396086:
+ { errorText = "ERR_ROLLBACK_START_TIMER";break;}
+ case -1074396087:
+ { errorText = "ERR_ROLLBACK_STOP_TIMER";break;}
+ case -1074396088:
+ { errorText = "ERR_ROLLBACK_RESIZE";break;}
+ case -1074396089:
+ { errorText = "ERR_ROLLBACK_RESOURCE_REINITIALIZE";break;}
+ case -1074396090:
+ { errorText = "ERR_ROLLBACK_RESOURCE_ENABLED";break;}
+ case -1074396091:
+ { errorText = "ERR_ROLLBACK_RESOURCE_UNINITIALIZED_ENABLE";break;}
+ case -1074396092:
+ { errorText = "ERR_ROLLBACK_RESOURCE_NON_EMPTY_INITIALIZE";break;}
+ case -1074396093:
+ { errorText = "ERR_ROLLBACK_RESOURCE_LOCKED";break;}
+ case -1074396094:
+ { errorText = "ERR_ROLLBACK_RESOURCE_CANNOT_UNLOCK";break;}
+ case -1074396095:
+ { errorText = "ERR_CALIBRATION_DUPLICATE_REFERENCE_POINT";break;}
+ case -1074396096:
+ { errorText = "ERR_NOT_AN_OBJECT";break;}
+ case -1074396097:
+ { errorText = "ERR_INVALID_PARTICLE_PARAMETER_VALUE";break;}
+ case -1074396098:
+ { errorText = "ERR_RESERVED_MUST_BE_NULL";break;}
+ case -1074396099:
+ { errorText = "ERR_CALIBRATION_INFO_SIMPLE_TRANSFORM";break;}
+ case -1074396100:
+ { errorText = "ERR_CALIBRATION_INFO_PERSPECTIVE_PROJECTION";break;}
+ case -1074396101:
+ { errorText = "ERR_CALIBRATION_INFO_MICRO_PLANE";break;}
+ case -1074396102:
+ { errorText = "ERR_CALIBRATION_INFO_6";break;}
+ case -1074396103:
+ { errorText = "ERR_CALIBRATION_INFO_5";break;}
+ case -1074396104:
+ { errorText = "ERR_CALIBRATION_INFO_4";break;}
+ case -1074396105:
+ { errorText = "ERR_CALIBRATION_INFO_3";break;}
+ case -1074396106:
+ { errorText = "ERR_CALIBRATION_INFO_2";break;}
+ case -1074396107:
+ { errorText = "ERR_CALIBRATION_INFO_1";break;}
+ case -1074396108:
+ { errorText = "ERR_CALIBRATION_ERRORMAP";break;}
+ case -1074396109:
+ { errorText = "ERR_CALIBRATION_INVALID_SCALING_FACTOR";break;}
+ case -1074396110:
+ { errorText = "ERR_CALIBRATION_INFO_VERSION";break;}
+ case -1074396111:
+ { errorText = "ERR_CALIBRATION_FAILED_TO_FIND_GRID";break;}
+ case -1074396112:
+ { errorText = "ERR_INCOMP_MATRIX_SIZE";break;}
+ case -1074396113:
+ { errorText = "ERR_CALIBRATION_IMAGE_UNCALIBRATED";break;}
+ case -1074396114:
+ { errorText = "ERR_CALIBRATION_INVALID_ROI";break;}
+ case -1074396115:
+ { errorText = "ERR_CALIBRATION_IMAGE_CORRECTED";break;}
+ case -1074396116:
+ { errorText = "ERR_CALIBRATION_INSF_POINTS";break;}
+ case -1074396117:
+ { errorText = "ERR_MATRIX_SIZE";break;}
+ case -1074396118:
+ { errorText = "ERR_INVALID_STEP_SIZE";break;}
+ case -1074396119:
+ { errorText = "ERR_CUSTOMDATA_INVALID_KEY";break;}
+ case -1074396120:
+ { errorText = "ERR_NOT_IMAGE";break;}
+ case -1074396121:
+ { errorText = "ERR_SATURATION_THRESHOLD_OUT_OF_RANGE";break;}
+ case -1074396122:
+ { errorText = "ERR_DRAWTEXT_COLOR_MUST_BE_GRAYSCALE";break;}
+ case -1074396123:
+ { errorText = "ERR_INVALID_CALIBRATION_MODE";break;}
+ case -1074396124:
+ { errorText = "ERR_INVALID_CALIBRATION_ROI_MODE";break;}
+ case -1074396125:
+ { errorText = "ERR_INVALID_CONTRAST_THRESHOLD";break;}
+ case -1074396126:
+ { errorText = "ERR_ROLLBACK_RESOURCE_CONFLICT_1";break;}
+ case -1074396127:
+ { errorText = "ERR_ROLLBACK_RESOURCE_CONFLICT_2";break;}
+ case -1074396128:
+ { errorText = "ERR_ROLLBACK_RESOURCE_CONFLICT_3";break;}
+ case -1074396129:
+ { errorText = "ERR_ROLLBACK_UNBOUNDED_INTERFACE";break;}
+ case -1074396130:
+ { errorText = "ERR_NOT_RECT_OR_ROTATED_RECT";break;}
+ case -1074396132:
+ { errorText = "ERR_MASK_NOT_TEMPLATE_SIZE";break;}
+ case -1074396133:
+ { errorText = "ERR_THREAD_COULD_NOT_INITIALIZE";break;}
+ case -1074396134:
+ { errorText = "ERR_THREAD_INITIALIZING";break;}
+ case -1074396135:
+ { errorText = "ERR_INVALID_BUTTON_LABEL";break;}
+ case -1074396136:
+ { errorText = "ERR_DIRECTX_INVALID_FILTER_QUALITY";break;}
+ case -1074396137:
+ { errorText = "ERR_DIRECTX_DLL_NOT_FOUND";break;}
+ case -1074396138:
+ { errorText = "ERR_ROLLBACK_NOT_SUPPORTED";break;}
+ case -1074396139:
+ { errorText = "ERR_ROLLBACK_RESOURCE_OUT_OF_MEMORY";break;}
+ case -1074396140:
+ { errorText = "ERR_BARCODE_CODE128_SET";break;}
+ case -1074396141:
+ { errorText = "ERR_BARCODE_CODE128_FNC";break;}
+ case -1074396142:
+ { errorText = "ERR_BARCODE_INVALID";break;}
+ case -1074396143:
+ { errorText = "ERR_BARCODE_TYPE";break;}
+ case -1074396144:
+ { errorText = "ERR_BARCODE_CODE93_SHIFT";break;}
+ case -1074396145:
+ { errorText = "ERR_BARCODE_UPCA";break;}
+ case -1074396146:
+ { errorText = "ERR_BARCODE_MSI";break;}
+ case -1074396147:
+ { errorText = "ERR_BARCODE_I25";break;}
+ case -1074396148:
+ { errorText = "ERR_BARCODE_EAN13";break;}
+ case -1074396149:
+ { errorText = "ERR_BARCODE_EAN8";break;}
+ case -1074396150:
+ { errorText = "ERR_BARCODE_CODE128";break;}
+ case -1074396151:
+ { errorText = "ERR_BARCODE_CODE93";break;}
+ case -1074396152:
+ { errorText = "ERR_BARCODE_CODE39";break;}
+ case -1074396153:
+ { errorText = "ERR_BARCODE_CODABAR";break;}
+ case -1074396154:
+ { errorText = "ERR_IMAGE_TOO_SMALL";break;}
+ case -1074396155:
+ { errorText = "ERR_UNINIT";break;}
+ case -1074396156:
+ { errorText = "ERR_NEED_FULL_VERSION";break;}
+ case -1074396157:
+ { errorText = "ERR_UNREGISTERED";break;}
+ case -1074396158:
+ { errorText = "ERR_MEMORY_ERROR";break;}
+ case -1074396159:
+ { errorText = "ERR_OUT_OF_MEMORY";break;}
+ case -1074396160:
+ { errorText = "ERR_SYSTEM_ERROR";break;}
+ case 0:
+ { errorText = "ERR_SUCCESS";break;}
+ // end National Instruments defined errors
+
+ // begin BAE defined errors
+ case ERR_VISION_GENERAL_ERROR:
+ { errorText = "ERR_VISION_GENERAL_ERROR";break;}
+ case ERR_COLOR_NOT_FOUND:
+ { errorText = "ERR_COLOR_NOT_FOUND";break;}
+ case ERR_PARTICLE_TOO_SMALL:
+ { errorText = "ERR_PARTICLE_TOO_SMALL";break;}
+ case ERR_CAMERA_FAILURE:
+ { errorText = "ERR_CAMERA_FAILURE";break;}
+ case ERR_CAMERA_SOCKET_CREATE_FAILED:
+ { errorText = "ERR_CAMERA_SOCKET_CREATE_FAILED";break;}
+ case ERR_CAMERA_CONNECT_FAILED:
+ { errorText = "ERR_CAMERA_CONNECT_FAILED";break;}
+ case ERR_CAMERA_STALE_IMAGE:
+ { errorText = "ERR_CAMERA_STALE_IMAGE";break;}
+ case ERR_CAMERA_NOT_INITIALIZED:
+ { errorText = "ERR_CAMERA_NOT_INITIALIZED";break;}
+ case ERR_CAMERA_NO_BUFFER_AVAILABLE:
+ { errorText = "ERR_CAMERA_NO_BUFFER_AVAILABLE";break;}
+ case ERR_CAMERA_HEADER_ERROR:
+ { errorText = "ERR_CAMERA_HEADER_ERROR";break;}
+ case ERR_CAMERA_BLOCKING_TIMEOUT:
+ { errorText = "ERR_CAMERA_BLOCKING_TIMEOUT";break;}
+ case ERR_CAMERA_AUTHORIZATION_FAILED:
+ { errorText = "ERR_CAMERA_AUTHORIZATION_FAILED";break;}
+ case ERR_CAMERA_TASK_SPAWN_FAILED:
+ { errorText = "ERR_CAMERA_TASK_SPAWN_FAILED";break;}
+ case ERR_CAMERA_TASK_INPUT_OUT_OF_RANGE:
+ { errorText = "ERR_CAMERA_TASK_INPUT_OUT_OF_RANGE";break;}
+ case ERR_CAMERA_COMMAND_FAILURE:
+ { errorText = "ERR_CAMERA_COMMAND_FAILURE";break;}
+ }
+
+ return errorText;
+}
+
+
+
diff --git a/aos/externals/WPILib/WPILib/Vision2009/FrcError.h b/aos/externals/WPILib/WPILib/Vision2009/FrcError.h
new file mode 100644
index 0000000..95a0356
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision2009/FrcError.h
@@ -0,0 +1,41 @@
+/********************************************************************************
+* Project : FIRST Motor Controller
+* File Name : FrcError.h
+* Contributors : JDG, ELF
+* Creation Date : August 12, 2008
+* Revision History : Source code & revision history maintained at sourceforge.WPI.edu
+* File Description : Error handling values for C routines
+*/
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. */
+/* Must be accompanied by the BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __FRCERROR_H__
+#define __FRCERROR_H__
+
+/* Error Codes */
+#define ERR_VISION_GENERAL_ERROR 166000 //
+#define ERR_COLOR_NOT_FOUND 166100 // TrackAPI.cpp
+#define ERR_PARTICLE_TOO_SMALL 166101 // TrackAPI.cpp
+
+#define ERR_CAMERA_FAILURE 166200 // AxisCamera.cpp
+#define ERR_CAMERA_SOCKET_CREATE_FAILED 166201 // AxisCamera.cpp
+#define ERR_CAMERA_CONNECT_FAILED 166202 // AxisCamera.cpp
+#define ERR_CAMERA_STALE_IMAGE 166203 // AxisCamera.cpp
+#define ERR_CAMERA_NOT_INITIALIZED 166204 // AxisCamera.cpp
+#define ERR_CAMERA_NO_BUFFER_AVAILABLE 166205 // AxisCamera.cpp
+#define ERR_CAMERA_HEADER_ERROR 166206 // AxisCamera.cpp
+#define ERR_CAMERA_BLOCKING_TIMEOUT 166207 // AxisCamera.cpp
+#define ERR_CAMERA_AUTHORIZATION_FAILED 166208 // AxisCamera.cpp
+#define ERR_CAMERA_TASK_SPAWN_FAILED 166209 // AxisCamera.cpp
+#define ERR_CAMERA_TASK_INPUT_OUT_OF_RANGE 166210 // AxisCamera.cpp
+#define ERR_CAMERA_COMMAND_FAILURE 166211 // AxisCamera.cpp
+
+/* error handling functions */
+int GetLastVisionError();
+char* GetVisionErrorText(int errorCode);
+
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Vision2009/TrackAPI.cpp b/aos/externals/WPILib/WPILib/Vision2009/TrackAPI.cpp
new file mode 100644
index 0000000..1bc594a
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision2009/TrackAPI.cpp
@@ -0,0 +1,481 @@
+/********************************************************************************
+* Project : FIRST Motor Controller
+* File Name : TrackAPI.cpp
+* Contributors : ELF, DWD
+* Creation Date : August 10, 2008
+* Revision History : Source code & revision history maintained at sourceforge.WPI.edu
+* File Description : Tracking Routines for FIRST Vision API
+*/
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "string.h"
+#include "vxWorks.h"
+
+#include "AxisCamera.h"
+#include "FrcError.h"
+#include "TrackAPI.h"
+#include "VisionAPI.h"
+
+int TrackAPI_debugFlag = 0;
+#define DPRINTF if(TrackAPI_debugFlag)dprintf
+
+/**
+* @brief Find the largest particle that meets a criteria
+* @param binaryImage Image to inspect
+* @param rect area to search
+* @return 0 = error
+*/
+bool InArea(Image* binaryImage, int particleIndex, Rect rect)
+{
+ double position;
+
+ imaqMeasureParticle(binaryImage, particleIndex, 0,
+ IMAQ_MT_BOUNDING_RECT_LEFT, &position);
+ if ( position < (rect.left ) ) return false; // outside left of rectangle?
+
+ imaqMeasureParticle(binaryImage, particleIndex, 0,
+ IMAQ_MT_BOUNDING_RECT_TOP, &position);
+ if ( position < (rect.top ) ) return false; // outside top of rectangle ?
+
+ imaqMeasureParticle(binaryImage, particleIndex, 0,
+ IMAQ_MT_BOUNDING_RECT_RIGHT, &position);
+ if (position > (rect.left + rect.width) ) return false; // outside right of rectangle ?
+
+ imaqMeasureParticle(binaryImage, particleIndex, 0,
+ IMAQ_MT_BOUNDING_RECT_BOTTOM, &position);
+ if (position > (rect.top + rect.height) ) return false; // outside bottom of rectangle ?
+
+ DPRINTF(LOG_INFO, "particle %i is in (%i %i) height %i width %i\n",
+ particleIndex, rect.left, rect.top, rect.height, rect.width);
+ return true;
+}
+
+/**
+* @brief Find the largest particle that meets a criteria
+* @param binaryImage Image to inspect
+* @param largestParticleIndex Index of the largest particle
+* @param rect area to search
+* @return 0 = error
+*/
+int GetLargestParticle(Image* binaryImage, int* largestParticleIndex)
+{ return GetLargestParticle(binaryImage, largestParticleIndex, IMAQ_NO_RECT); }
+
+int GetLargestParticle(Image* binaryImage, int* largestParticleIndex, Rect rect)
+{
+ *largestParticleIndex = 0; // points to caller-provided variable
+
+ /* determine number of particles in thresholded image */
+ int numParticles;
+ int success = frcCountParticles(binaryImage, &numParticles);
+ if ( !success ) { return success; }
+
+ /* if no particles found we can quit here */
+ if (numParticles == 0) { return 0; } // unsuccessful if zero particles found
+
+ // find the largest particle
+ double largestParticleArea = 0;
+ double particleArea;
+ for (int i = 0; i < numParticles; ++i) {
+ success = imaqMeasureParticle(binaryImage, i, 0, IMAQ_MT_AREA, &particleArea);
+ if ( !success ) { return success; }
+ if (particleArea > largestParticleArea) {
+ // see if is in the right area
+ if ( InArea(binaryImage, i, rect) ) {
+ largestParticleArea = particleArea;
+ *largestParticleIndex = i; // return index to caller
+ }
+ }
+ }
+
+ return success;
+}
+
+/**
+* @brief Search for a color. Supports IMAQ_IMAGE_HSL.
+* @param color Definition for the hue range
+* @param trackReport Values for tracking: center of particle, particle size, color
+* @return 0 = error
+*/
+int FindColor(FrcHue color, ParticleAnalysisReport* trackReport)
+{
+ int success = 0; // return: 0 = error
+
+ /* track color */
+ // use ACTIVE_LIGHT or WHITE_LIGHT for brightly lit objects
+ TrackingThreshold td = GetTrackingData(color, PASSIVE_LIGHT);
+
+ success = FindColor(IMAQ_HSL, &td.hue, &td.saturation, &td.luminance, trackReport);
+ if ( !success ) {
+ DPRINTF (LOG_INFO, "did not find color - errorCode= %i",GetLastVisionError());
+ return success;
+ }
+
+ //PrintReport(par);
+
+ /* set an image quality restriction */
+ if (trackReport->particleToImagePercent < PARTICLE_TO_IMAGE_PERCENT) {
+ imaqSetError(ERR_PARTICLE_TOO_SMALL, __FUNCTION__);
+ success = 0;
+ }
+ return success;
+}
+
+/**
+* @brief Search for a color. Supports IMAQ_IMAGE_HSL.
+* @param hueRange The range for the first plane
+* @param trackReport Values for tracking: center of particle, particle size, color
+* @return 0 = error
+*/
+int FindColor(const Range* hueRange, ParticleAnalysisReport *trackReport)
+{ return FindColor(hueRange, DEFAULT_SATURATION_THRESHOLD, trackReport); }
+
+/**
+* @brief Search for a color. Supports IMAQ_IMAGE_HSL.
+* @param hueRange The range for the first plane
+* @param minSaturation The lower range saturation
+* @param trackReport Values for tracking: center of particle, particle size, color
+* @return 0 = error
+*/
+int FindColor(const Range* hueRange, int minSaturation, ParticleAnalysisReport *trackReport)
+{
+ Range satRange;
+ satRange.minValue = minSaturation;
+ satRange.maxValue = 255;
+ Range lumRange;
+ lumRange.minValue = 0;
+ lumRange.maxValue = 255;
+ ColorMode cmode = IMAQ_HSL;
+ return FindColor(cmode, hueRange, &satRange, &lumRange, trackReport);
+}
+
+/**
+* @brief Search for a color. Supports IMAQ_IMAGE_HSL and IMAQ_IMAGE_RGB.
+* @param mode Color mode, either IMAQ_HSL or IMAQ_RGB
+* @param plane1Range The range for the first plane (hue or red)
+* @param plane2Range The range for the second plane (saturation or green)
+* @param plane3Range The range for the third plane (luminance or blue)
+* @param trackReport Values for tracking: center of particle, particle size, etc
+* @return 0 = error
+*/
+int FindColor(ColorMode mode, const Range* plane1Range, const Range* plane2Range,
+ const Range* plane3Range, ParticleAnalysisReport *trackReport)
+{
+ return FindColor(mode, plane1Range, plane2Range, plane3Range, trackReport, NULL);
+}
+
+/**
+* @brief Search for a color. Supports IMAQ_IMAGE_HSL and IMAQ_IMAGE_RGB.
+* @param mode Color mode, either IMAQ_HSL or IMAQ_RGB
+* @param plane1Range The range for the first plane (hue or red)
+* @param plane2Range The range for the second plane (saturation or green)
+* @param plane3Range The range for the third plane (luminance or blue)
+* @param trackReport Values for tracking: center of particle, particle size, etc
+* @param colorReport Color charactaristics of the particle
+* @return 0 = error
+*/
+int FindColor(ColorMode mode, const Range* plane1Range, const Range* plane2Range,
+ const Range* plane3Range, ParticleAnalysisReport *trackReport,
+ ColorReport *colorReport)
+{
+ return FindColor(mode, plane1Range, plane2Range, plane3Range, trackReport,
+ NULL, IMAQ_NO_RECT);
+}
+
+/**
+* @brief Search for a color. Supports IMAQ_IMAGE_HSL and IMAQ_IMAGE_RGB.
+* @param mode Color mode, either IMAQ_HSL or IMAQ_RGB
+* @param plane1Range The range for the first plane (hue or red)
+* @param plane2Range The range for the second plane (saturation or green)
+* @param plane3Range The range for the third plane (luminance or blue)
+* @param trackReport Values for tracking: center of particle, particle size, etc
+* @param colorReport Color charactaristics of the particle
+* @param rect Rectangle to confine search to
+* @return 0 = error
+*/
+int FindColor(ColorMode mode, const Range* plane1Range, const Range* plane2Range,
+ const Range* plane3Range, ParticleAnalysisReport *trackReport,
+ ColorReport *colorReport, Rect rect)
+{
+ int errorCode = 0;
+ int success = 0;
+
+ /* create an image object */
+ Image* cameraImage = frcCreateImage(IMAQ_IMAGE_HSL);
+ if (!cameraImage) { return success; }
+
+ /* get image from camera - if the camera has not finished initializing,
+ * this will fail
+ */
+ double imageTime;
+ success = GetImage(cameraImage, &imageTime);
+ if (!success){
+ DPRINTF(LOG_INFO, "No camera Image available Error = %i %s",
+ errorCode, GetVisionErrorText(errorCode));
+ frcDispose(cameraImage);
+ imaqSetError(errorCode, __FUNCTION__); //reset error code for the caller
+ return success;
+ }
+
+ /* save a copy of the image to another image for color thresholding later */
+ Image* histImage = frcCreateImage(IMAQ_IMAGE_HSL);
+ if (!histImage) { frcDispose(cameraImage); return success; }
+ success = frcCopyImage(histImage,cameraImage);
+ if ( !success ) {
+ errorCode = GetLastVisionError();
+ frcDispose(__FUNCTION__,cameraImage,histImage,NULL);
+ return success;
+ }
+
+ /* Color threshold the image */
+ success = frcColorThreshold(cameraImage, cameraImage, mode, plane1Range, plane2Range, plane3Range);
+ if ( !success ) {
+ errorCode = GetLastVisionError();
+ DPRINTF (LOG_DEBUG, "Error = %i %s ", errorCode, GetVisionErrorText(errorCode));
+ frcDispose(__FUNCTION__,cameraImage,histImage,NULL);
+ return success;
+ }
+
+ int largestParticleIndex = 0;
+ success = GetLargestParticle(cameraImage, &largestParticleIndex, rect );
+ if ( !success ) {
+ errorCode = GetLastVisionError();
+ DPRINTF (LOG_DEBUG, "Error after GetLargestParticle = %i %s ", errorCode, GetVisionErrorText(errorCode));
+ frcDispose(__FUNCTION__,cameraImage,histImage,NULL);
+ imaqSetError(ERR_COLOR_NOT_FOUND, __FUNCTION__);
+ return success;
+ }
+ DPRINTF(LOG_INFO, "largestParticleIndex = %i\n", largestParticleIndex);
+
+ /* Particles were found */
+ /*
+ * Fill in report information for largest particle found
+ */
+ success = frcParticleAnalysis(cameraImage, largestParticleIndex, trackReport);
+ trackReport->imageTimestamp = imageTime;
+
+ /* clean up */
+ if (!success) {frcDispose(__FUNCTION__,cameraImage,histImage,NULL); return success;}
+
+ /* particle color statistics */
+ /* only if a color report requested */
+ if (colorReport != NULL)
+ {
+ /* first filter out the other particles */
+ ParticleFilterCriteria2 criteria;
+ ParticleFilterOptions* options = NULL;
+ Rect rect;
+ int numParticles;
+ success = frcParticleFilter(cameraImage, cameraImage, &criteria, 1, options,
+ rect, &numParticles);
+ if ( !success ) {
+ DPRINTF(LOG_INFO, "frcParticleFilter errorCode %i", GetLastVisionError());
+ }
+
+ /* histogram the original image using the thresholded image as a mask */
+ int numClasses = 10; //how many classes?
+ ColorHistogramReport* chrep = imaqColorHistogram2(histImage, numClasses, IMAQ_HSL,
+ NULL, cameraImage);
+ if (chrep == NULL) {
+ DPRINTF(LOG_INFO, "NULL Color Histogram");
+ errorCode = GetLastVisionError();
+ } else {
+ colorReport->particleHueMax = chrep->plane1.max;
+ colorReport->particleHueMin = chrep->plane1.min;
+ colorReport->particleHueMean = chrep->plane1.mean;
+ colorReport->particleSatMax = chrep->plane2.max;
+ colorReport->particleSatMin = chrep->plane2.min;
+ colorReport->particleSatMean = chrep->plane2.mean;
+ colorReport->particleLumMax = chrep->plane3.max;
+ colorReport->particleLumMin = chrep->plane3.min;
+ colorReport->particleLumMean = chrep->plane3.mean;
+ colorReport->numberParticlesFound = numParticles;
+ frcDispose(chrep);
+ }
+ }
+
+ /* clean up */
+ frcDispose(__FUNCTION__,cameraImage,histImage,NULL);
+
+ return success;
+}
+
+
+/**
+ * Data functions for tracking
+ */
+
+
+/**
+ * @brief Get default HSL tracking parameters
+ * Note these parameters are not fully characterized at this point
+ * Get these default values and modify them as needed for your environment
+ * @param hue tasked color
+ * @param light saturation/luminance
+ */
+TrackingThreshold GetTrackingData(FrcHue hue, FrcLight light)
+{
+ TrackingThreshold trackingData;
+
+ //set saturation & luminance
+ switch (light) {
+ default:
+ case FLUORESCENT:
+ trackingData.saturation.minValue = 100;
+ trackingData.saturation.maxValue = 255;
+ trackingData.luminance.minValue = 40;
+ trackingData.luminance.maxValue = 255;
+ if (hue == GREEN) trackingData.luminance.minValue = 100;
+ if (hue == PINK) trackingData.saturation.minValue = 80;
+ if (hue == PINK) trackingData.luminance.minValue = 60;
+ if (hue == PINK) trackingData.luminance.maxValue = 155;
+ break;
+ case PASSIVE_LIGHT:
+ trackingData.saturation.minValue = 50;
+ trackingData.saturation.maxValue = 255;
+ trackingData.luminance.minValue = 20;
+ trackingData.luminance.maxValue = 255;
+ break;
+ case BRIGHT_LIGHT:
+ trackingData.saturation.minValue = 0;
+ trackingData.saturation.maxValue = 100;
+ trackingData.luminance.minValue = 100;
+ trackingData.luminance.maxValue = 255;
+ break;
+ case ACTIVE_LIGHT:
+ trackingData.saturation.minValue = 0;
+ trackingData.saturation.maxValue = 50;
+ trackingData.luminance.minValue = 150;
+ trackingData.luminance.maxValue = 255;
+ break;
+ case WHITE_LIGHT:
+ trackingData.saturation.minValue = 0;
+ trackingData.saturation.maxValue = 20;
+ trackingData.luminance.minValue = 200;
+ trackingData.luminance.maxValue = 255;
+ break;
+ }
+
+ //set hue
+ switch (hue){
+ default:
+ case WHITE:
+ strcpy (trackingData.name, "WHITE");
+ trackingData.hue.minValue = 0;
+ trackingData.hue.maxValue = 255;
+ break;
+ case ORANGE:
+ strcpy (trackingData.name, "ORANGE");
+ trackingData.hue.minValue = 5;
+ trackingData.hue.maxValue = 25;
+ break;
+ case YELLOW:
+ strcpy (trackingData.name, "YELLOW");
+ trackingData.hue.minValue = 30;
+ trackingData.hue.maxValue = 50;
+ break;
+ case GREEN:
+ strcpy (trackingData.name, "GREEN");
+ if (light == FLUORESCENT) {
+ trackingData.hue.minValue = 60;
+ trackingData.hue.maxValue = 110;
+ } else {
+ trackingData.hue.minValue = 90;
+ trackingData.hue.maxValue = 125;
+ }
+ break;
+ case BLUE:
+ strcpy (trackingData.name, "BLUE");
+ trackingData.hue.minValue = 140;
+ trackingData.hue.maxValue = 170;
+ break;
+ case PURPLE:
+ strcpy (trackingData.name, "PURPLE");
+ trackingData.hue.minValue = 180;
+ trackingData.hue.maxValue = 200;
+ break;
+ case PINK:
+ strcpy (trackingData.name, "PINK");
+ trackingData.hue.minValue = 210;
+ trackingData.hue.maxValue = 250;
+ break;
+ case RED:
+ strcpy (trackingData.name, "RED");
+ trackingData.hue.minValue = 240;
+ trackingData.hue.maxValue = 255;
+ break;
+ }
+ return(trackingData);
+}
+
+
+/**
+ * Print particle analysis report
+ * @param myReport Report to print
+ */
+void PrintReport(ParticleAnalysisReport* myReport)
+{
+ dprintf(LOG_INFO, "particle analysis:\n %s%i %s%i\n %s%lf\n %s%i %s%i\n %s%g %s%g\n %s%g\n %s%i %s%i\n %s%i %s%i\n",
+ "imageHeight = ", myReport->imageHeight,
+ "imageWidth = ", myReport->imageWidth,
+ "imageTimestamp = ", myReport->imageTimestamp,
+ "center_mass_x = ", myReport->center_mass_x,
+ "center_mass_y = ", myReport->center_mass_y,
+ "center_mass_x_normalized = ", myReport->center_mass_x_normalized,
+ "center_mass_y_normalized = ", myReport->center_mass_y_normalized,
+ "particleArea = ", myReport->particleArea,
+ "boundingRectangleTop = ", myReport->boundingRect.top,
+ "boundingRectangleLeft = ", myReport->boundingRect.left,
+ "boundingRectangleHeight = ", myReport->boundingRect.height,
+ "boundingRectangleWidth = ", myReport->boundingRect.width);
+
+ dprintf(LOG_INFO, "quality statistics: \n %s%g %s%g \n",
+ "particleToImagePercent = ", myReport->particleToImagePercent,
+ "particleQuality = ", myReport->particleQuality);
+}
+
+/**
+ * Print color report
+ * @param myReport Report to print
+ */
+void PrintReport(ColorReport* myReport)
+{
+ dprintf(LOG_INFO, "particle ranges for %i particles: ",
+ "numberParticlesFound = ", myReport->numberParticlesFound);
+ ;
+ dprintf(LOG_INFO, "\n %s%f %s%f %s%f\n %s%f %s%f %s%f\n %s%f %s%f %s%f\n -------",
+ "particleHueMax = ", myReport->particleHueMax,
+ "particleHueMin = ", myReport->particleHueMin,
+ "particleHueMean = ", myReport->particleHueMean,
+ "particleSatMax = ", myReport->particleSatMax,
+ "particleSatMin = ", myReport->particleSatMin,
+ "particleSatMean = ", myReport->particleSatMean,
+ "particleLumMax = ", myReport->particleLumMax,
+ "particleLumMin = ", myReport->particleLumMin,
+ "particleLumMean = ", myReport->particleLumMean);
+
+}
+
+/**
+ * Print color report
+ * @param myReport Report to print
+ */
+void PrintReport(TrackingThreshold* myReport)
+{
+ dprintf(LOG_INFO, "name of color: %s", myReport->name);
+
+ dprintf(LOG_INFO, "\n %s%i %s%i\n %s%i %s%i\n %s%i %s%i\n -------",
+ "hueMin = ", myReport->hue.minValue,
+ "hueMax = ", myReport->hue.maxValue,
+ "satMin = ", myReport->saturation.minValue,
+ "satMax = ", myReport->saturation.maxValue,
+ "lumMin = ", myReport->luminance.minValue,
+ "lumMax = ", myReport->luminance.maxValue );
+
+}
+
+
+
diff --git a/aos/externals/WPILib/WPILib/Vision2009/TrackAPI.h b/aos/externals/WPILib/WPILib/Vision2009/TrackAPI.h
new file mode 100644
index 0000000..2f72d66
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision2009/TrackAPI.h
@@ -0,0 +1,74 @@
+/********************************************************************************
+* Project : FIRST Motor Controller
+* File Name : TrackAPI.h
+* Contributors : ELF
+* Creation Date : August 12, 2008
+* Revision History : Source code & revision history maintained at sourceforge.WPI.edu
+* File Description : Globally defined values for the FIRST Vision API
+*/
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __TRACKAPI_H__
+#define __TRACKAPI_H__
+
+#include "VisionAPI.h"
+#include "BaeUtilities.h"
+
+/* Constants */
+/** image quality requirement: particle must be this % of pixels
+ * For instance, a 320x240 image has 76800 pixels. With this
+ * tolerance at .01, the image must be 768 pixels.
+ * Use a percentage instead of a fixed # of pixels so different
+ * image sizes will work the same way */
+#define PARTICLE_TO_IMAGE_PERCENT 0.01
+
+/* Structures */
+typedef struct TrackingThreshold_struct {
+ char name[64];
+ Range hue;
+ Range saturation;
+ Range luminance;
+} TrackingThreshold;
+
+/* Enumerated Types */
+
+/** Predefined hues */
+typedef enum FrcHue_enum {
+ // Basic colors
+ RED, GREEN, BLUE, YELLOW, ORANGE, PURPLE, WHITE, PINK
+}FrcHue;
+
+/** Predefined saturation / luminance settings */
+typedef enum FrcLight_enum {
+ PASSIVE_LIGHT, BRIGHT_LIGHT, ACTIVE_LIGHT, WHITE_LIGHT, FLUORESCENT
+}FrcLight;
+
+/* color tracking support functions */
+TrackingThreshold GetTrackingData(FrcHue hue, FrcLight light);
+
+void PrintReport(ParticleAnalysisReport* myReport);
+void PrintReport(ColorReport* myReport);
+void PrintReport(TrackingThreshold* myReport);
+
+/* Tracking functions */
+
+/* find a color in current camera image */
+bool InArea(Image* binaryImage, int particleIndex, Rect rect);
+int GetLargestParticle(Image* binaryImage, int* particleNum);
+int GetLargestParticle(Image* binaryImage, int* particleNum, Rect rect);
+int FindColor(FrcHue color, ParticleAnalysisReport* trackReport);
+int FindColor(const Range* hueRange, ParticleAnalysisReport *trackReport);
+int FindColor(const Range* hueRange, int minSaturation, ParticleAnalysisReport *trackReport);
+int FindColor(ColorMode mode, const Range* plane1Range, const Range* plane2Range,
+ const Range* plane3Range, ParticleAnalysisReport *trackReport);
+int FindColor(ColorMode mode, const Range* plane1Range, const Range* plane2Range,
+ const Range* plane3Range, ParticleAnalysisReport *trackReport, ColorReport *colorReport);
+int FindColor(ColorMode mode, const Range* plane1Range, const Range* plane2Range,
+ const Range* plane3Range, ParticleAnalysisReport *trackReport,
+ ColorReport *colorReport, Rect rect);
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/Vision2009/VisionAPI.cpp b/aos/externals/WPILib/WPILib/Vision2009/VisionAPI.cpp
new file mode 100644
index 0000000..f511b39
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision2009/VisionAPI.cpp
@@ -0,0 +1,676 @@
+/********************************************************************************
+* Project : FIRST Motor Controller
+* File Name : VisionAPI.cpp
+* Contributors : ELF, EMF
+* Creation Date : June 26, 2008
+* Revision History : Source code & revision history maintained at sourceforge.WPI.edu
+* File Description : C Routines for FIRST Vision API. Open source API developed
+* by BAE Systems to interface with the National Instruments vision C library
+* in the nivision.out module. The published interface to nivision.out is in
+* the header file nivision.h and documented in the NIVisionCVI.chm help file.
+*/
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "stdioLib.h"
+#include "vxWorks.h"
+
+#include "BaeUtilities.h"
+#include "FrcError.h"
+#include "VisionAPI.h"
+
+int VisionAPI_debugFlag = 1;
+#define DPRINTF if(VisionAPI_debugFlag)dprintf
+
+/* Image Management functions */
+
+/**
+* @brief Create an image object
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_COMPLEX, IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL, IMAQ_IMAGE_RGB_U64
+* The border size is defaulted to 3 so that convolutional algorithms work at the edges.
+* When you are finished with the created image, dispose of it by calling frcDispose().
+* To get extended error information, call GetLastError().
+*
+* @param type Type of image to create
+* @return Image* On success, this function returns the created image. On failure, it returns NULL.
+*/
+Image* frcCreateImage(ImageType type) { return imaqCreateImage(type, DEFAULT_BORDER_SIZE); }
+
+/**
+* @brief Dispose of one object. Supports any object created on the heap.
+*
+* @param object object to dispose of
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcDispose(void* object) { return imaqDispose(object); }
+/**
+* @brief Dispose of a list of objects. Supports any object created on the heap.
+*
+* @param functionName The name of the function
+* @param ... A list of pointers to structures that need to be disposed of.
+* The last pointer in the list should always be set to NULL.
+*
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcDispose( const char* functionName, ... ) /* Variable argument list */
+{
+ va_list disposalPtrList; /* Input argument list */
+ void* disposalPtr; /* For iteration */
+ int success, returnValue = 1;
+
+ va_start( disposalPtrList, functionName ); /* start of variable list */
+ disposalPtr = va_arg( disposalPtrList, void* );
+ while( disposalPtr != NULL ) {
+ success = imaqDispose(disposalPtr);
+ if (!success) {returnValue = 0;}
+ disposalPtr = va_arg( disposalPtrList, void* );
+ }
+ return returnValue;
+}
+
+/**
+* @brief Copy an image object.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL.
+*
+* @param dest Copy of image. On failure, dest is NULL. Must have already been created using frcCreateImage().
+* When you are finished with the created image, dispose of it by calling frcDispose().
+* @param source Image to copy
+*
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcCopyImage(Image* dest, const Image* source) { return imaqDuplicate(dest, source); }
+
+/**
+* @brief Crop image without changing the scale.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL.
+*
+* @param dest Modified image
+* @param source Image to crop
+* @param rect region to process, or IMAQ_NO_RECT
+*
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcCrop(Image* dest, const Image* source, Rect rect)
+{
+ return imaqScale(dest, source, 1, 1, IMAQ_SCALE_LARGER, rect);
+}
+
+
+/**
+* @brief Scales the entire image larger or smaller.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL.
+*
+* @param dest Modified image
+* @param source Image to scale
+* @param xScale the horizontal reduction ratio
+* @param yScale the vertical reduction ratio
+* @param scaleMode IMAQ_SCALE_LARGER or IMAQ_SCALE_SMALLER
+*
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcScale(Image* dest, const Image* source, int xScale, int yScale, ScalingMode scaleMode)
+{
+ Rect rect = IMAQ_NO_RECT;
+ return imaqScale(dest, source, xScale, yScale, scaleMode, rect);
+}
+
+/**
+ * @brief Creates image object from the information in a file. The file can be in one of the following formats:
+ * PNG, JPEG, JPEG2000, TIFF, AIPD, or BMP.
+ * Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_COMPLEX, IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL, IMAQ_IMAGE_RGB_U64.
+ *
+ * @param image Image read in
+ * @param fileName File to read. Cannot be NULL
+ *
+ * @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+ */
+ int frcReadImage(Image* image, const char* fileName)
+ {
+ return imaqReadFile(image, fileName, NULL, NULL);
+ }
+
+
+ /**
+ * @brief Write image to a file.
+ * Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_COMPLEX, IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL, IMAQ_IMAGE_RGB_U64.
+ *
+ * The file type is determined by the extension, as follows:
+ *
+ * Extension File Type
+ * aipd or .apd AIPD
+ * .bmp BMP
+ * .jpg or .jpeg JPEG
+ * .jp2 JPEG2000
+ * .png PNG
+ * .tif or .tiff TIFF
+ *
+ *
+ *The following are the supported image types for each file type:
+ *
+ * File Types Image Types
+ * AIPD all image types
+ * BMP, JPEG 8-bit, RGB
+ * PNG, TIFF, JPEG2000 8-bit, 16-bit, RGB, RGBU64
+ *
+ * @param image Image to write
+ * @param fileName File to read. Cannot be NULL. The extension determines the file format that is written.
+ *
+ * @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+ */
+int frcWriteImage(const Image* image, const char* fileName)
+{
+ RGBValue* colorTable = NULL;
+ return imaqWriteFile(image, fileName, colorTable);
+}
+
+
+/* Measure Intensity functions */
+
+/**
+* @brief Measures the pixel intensities in a rectangle of an image.
+* Outputs intensity based statistics about an image such as Max, Min, Mean and Std Dev of pixel value.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL.
+*
+* Parameter Discussion :
+* Relevant parameters of the HistogramReport include:
+* min, max, mean and stdDev
+* min/max Setting both min and max to 0 causes the function to set min to 0
+* and the max to 255 for 8-bit images and to the actual minimum value and
+* maximum value of the image for all other image types.
+* maxSetting both min and max to 0 causes the function to set max to 255
+* for 8-bit images and to the actual maximum value of the image for
+* all other image types.
+*
+* @param image Image whose histogram the function calculates.
+* @param numClasses The number of classes into which the function separates the pixels.
+* Determines the number of elements in the histogram array returned
+* @param min The minimum pixel value to consider for the histogram.
+* The function does not count pixels with values less than min.
+* @param max The maximum pixel value to consider for the histogram.
+* The function does not count pixels with values greater than max.
+* @param rect Region of interest in the image. If not included, the entire image is used.
+* @return On success, this function returns a report describing the pixel value classification.
+* When you are finished with the report, dispose of it by calling frcDispose().
+* On failure, this function returns NULL. To get extended error information, call GetLastError().
+*
+*/
+HistogramReport* frcHistogram(const Image* image, int numClasses, float min, float max)
+{
+ Rect rect = IMAQ_NO_RECT;
+ return frcHistogram(image, numClasses, min, max, rect);
+}
+HistogramReport* frcHistogram(const Image* image, int numClasses, float min, float max, Rect rect)
+{
+ int success;
+ int fillValue = 1;
+
+ /* create the region of interest */
+ ROI* pRoi = imaqCreateROI();
+ success = imaqAddRectContour(pRoi, rect);
+ if ( !success ) { GetLastVisionError(); return NULL; }
+
+ /* make a mask from the ROI */
+ Image* pMask = frcCreateImage(IMAQ_IMAGE_U8);
+ success = imaqROIToMask(pMask, pRoi, fillValue, NULL, NULL);
+ if ( !success ) {
+ GetLastVisionError();
+ frcDispose(__FUNCTION__, pRoi, NULL);
+ return NULL;
+ }
+
+ /* get a histogram report */
+ HistogramReport* pHr = NULL;
+ pHr = imaqHistogram(image, numClasses, min, max, pMask);
+
+ /* clean up */
+ frcDispose(__FUNCTION__, pRoi, pMask, NULL);
+
+ return pHr;
+}
+
+/**
+* @brief Calculates the histogram, or pixel distribution, of a color image.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL.
+*
+* @param image Image whose histogram the function calculates.
+* @param numClasses The number of classes into which the function separates the pixels.
+* Determines the number of elements in the histogram array returned
+* @param mode The color space in which to perform the histogram. Possible values include IMAQ_RGB and IMAQ_HSL.
+* @param mask An optional mask image. This image must be an IMAQ_IMAGE_U8 image.
+* The function calculates the histogram using only those pixels in the image whose
+* corresponding pixels in the mask are non-zero. Set this parameter to NULL to calculate
+* the histogram of the entire image, or use the simplified call.
+*
+* @return On success, this function returns a report describing the classification
+* of each plane in a HistogramReport.
+* When you are finished with the report, dispose of it by calling frcDispose().
+* On failure, this function returns NULL.
+* To get extended error information, call imaqGetLastError().
+*/
+ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses, ColorMode mode)
+{
+ return frcColorHistogram(image, numClasses, mode, NULL);
+}
+
+ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses, ColorMode mode, Image* mask)
+{
+ return imaqColorHistogram2((Image*)image, numClasses, mode, NULL, mask);
+}
+
+
+/**
+* @brief Measures the pixel intensities in a rectangle of an image.
+* Outputs intensity based statistics about an image such as Max, Min, Mean and Std Dev of pixel value.
+* Supports IMAQ_IMAGE_U8 (grayscale) IMAQ_IMAGE_RGB (color) IMAQ_IMAGE_HSL (color-HSL).
+*
+* @param image The image whose pixel value the function queries
+* @param pixel The coordinates of the pixel that the function queries
+* @param value On return, the value of the specified image pixel. This parameter cannot be NULL.
+* This data structure contains either grayscale, RGB, HSL, Complex or RGBU64Value depending on the type of image.
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcGetPixelValue(const Image* image, Point pixel, PixelValue* value)
+{
+ return imaqGetPixel(image, pixel, value);
+}
+
+
+/* Particle Analysis functions */
+
+/**
+* @brief Filters particles out of an image based on their measurements.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL.
+*
+* @param dest The destination image. If dest is used, it must be the same size as the Source image. It will contain only the filtered particles.
+* @param source The image containing the particles to filter.
+* @param criteria An array of criteria to apply to the particles in the source image. This array cannot be NULL.
+* See the NIVisionCVI.chm help file for definitions of criteria.
+* @param criteriaCount The number of elements in the criteria array.
+* @param options Binary filter options, including rejectMatches, rejectBorder, and connectivity8.
+* @param rect Area of image to filter. If omitted, the default is entire image.
+* @param numParticles On return, the number of particles left in the image
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcParticleFilter(Image* dest, Image* source, const ParticleFilterCriteria2* criteria,
+ int criteriaCount, const ParticleFilterOptions* options, int* numParticles)
+{
+ Rect rect = IMAQ_NO_RECT;
+ return frcParticleFilter(dest, source, criteria, criteriaCount, options, rect, numParticles);
+}
+
+int frcParticleFilter(Image* dest, Image* source, const ParticleFilterCriteria2* criteria,
+ int criteriaCount, const ParticleFilterOptions* options, Rect rect, int* numParticles)
+{
+ ROI* roi = imaqCreateROI();
+ imaqAddRectContour(roi, rect);
+ return imaqParticleFilter3(dest, source, criteria, criteriaCount, options, roi, numParticles);
+}
+
+
+/**
+* @brief Performs morphological transformations on binary images.
+* Supports IMAQ_IMAGE_U8.
+*
+* @param dest The destination image. The border size of the destination image is not important.
+* @param source The image on which the function performs the morphological operations. The calculation
+* modifies the border of the source image. The border must be at least half as large as the larger
+* dimension of the structuring element. The connected source image for a morphological transformation
+* must have been created with a border capable of supporting the size of the structuring element.
+* A 3 by 3 structuring element requires a minimal border of 1, a 5 by 5 structuring element requires a minimal border of 2, and so on.
+* @param method The morphological transform to apply.
+* @param structuringElement The structuring element used in the operation. Omit this parameter if you do not want a custom structuring element.
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcMorphology(Image* dest, Image* source, MorphologyMethod method)
+{
+ return imaqMorphology(dest, source, method, NULL);
+}
+
+int frcMorphology(Image* dest, Image* source, MorphologyMethod method, const StructuringElement* structuringElement)
+{
+ return imaqMorphology(dest, source, method, structuringElement);
+}
+
+/**
+* @brief Eliminates particles that touch the border of the image.
+* Supports IMAQ_IMAGE_U8.
+*
+* @param dest The destination image.
+* @param source The source image. If the image has a border, the function sets all border pixel values to 0.
+* @param connectivity8 specifies the type of connectivity used by the algorithm for particle detection.
+* The connectivity mode directly determines whether an adjacent pixel belongs to the same particle or a
+* different particle. Set to TRUE to use connectivity-8 to determine whether particles are touching
+* Set to FALSE to use connectivity-4 to determine whether particles are touching.
+* The default setting for the simplified call is TRUE
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcRejectBorder(Image* dest, Image* source)
+{ return imaqRejectBorder(dest, source, TRUE); }
+
+int frcRejectBorder(Image* dest, Image* source, int connectivity8)
+{
+ return imaqRejectBorder(dest, source, connectivity8);
+}
+
+
+/**
+* @brief Counts the number of particles in a binary image.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL.
+* @param image binary (thresholded) image
+* @param numParticles On return, the number of particles.
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcCountParticles(Image* image, int* numParticles)
+{
+ return imaqCountParticles(image, 1, numParticles);
+}
+
+
+/**
+* @brief Conduct measurements for a single particle in an images.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL.
+*
+* @param image image with the particle to analyze. This function modifies the source image.
+* If you need the original image, create a copy of the image using frcCopy() before using this function.
+* @param particleNumber The number of the particle to get information on
+* @param par on return, a particle analysis report containing information about the particle. This structure must be created by the caller.
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcParticleAnalysis(Image* image, int particleNumber, ParticleAnalysisReport* par)
+{
+ int success = 0;
+
+ /* image information */
+ int height, width;
+ if ( ! imaqGetImageSize(image, &width, &height) ) { return success; }
+ par->imageWidth = width;
+ par->imageHeight = height;
+ par->particleIndex = particleNumber;
+
+ /* center of mass point of the largest particle */
+ double returnDouble;
+ success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_CENTER_OF_MASS_X, &returnDouble);
+ if ( !success ) { return success; }
+ par->center_mass_x = (int)returnDouble; // pixel
+
+ success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_CENTER_OF_MASS_Y, &returnDouble);
+ if ( !success ) { return success; }
+ par->center_mass_y = (int)returnDouble; // pixel
+
+ /* particle size statistics */
+ success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_AREA, &returnDouble);
+ if ( !success ) { return success; }
+ par->particleArea = returnDouble;
+
+ success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_BOUNDING_RECT_TOP, &returnDouble);
+ if ( !success ) { return success; }
+ par->boundingRect.top = (int)returnDouble;
+
+ success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_BOUNDING_RECT_LEFT, &returnDouble);
+ if ( !success ) { return success; }
+ par->boundingRect.left = (int)returnDouble;
+
+ success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_BOUNDING_RECT_HEIGHT, &returnDouble);
+ if ( !success ) { return success; }
+ par->boundingRect.height = (int)returnDouble;
+
+ success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_BOUNDING_RECT_WIDTH, &returnDouble);
+ if ( !success ) { return success; }
+ par->boundingRect.width = (int)returnDouble;
+
+ /* particle quality statistics */
+ success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_AREA_BY_IMAGE_AREA, &returnDouble);
+ if ( !success ) { return success; }
+ par->particleToImagePercent = returnDouble;
+
+ success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_AREA_BY_PARTICLE_AND_HOLES_AREA, &returnDouble);
+ if ( !success ) { return success; }
+ par->particleQuality = returnDouble;
+
+ /* normalized position (-1 to 1) */
+ par->center_mass_x_normalized = RangeToNormalized(par->center_mass_x, width);
+ par->center_mass_y_normalized = RangeToNormalized(par->center_mass_y, height);
+
+ return success;
+}
+
+
+/* Image Enhancement functions */
+
+/**
+* @brief Improves contrast on a grayscale image.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16.
+* @param dest The destination image.
+* @param source The image to equalize
+* @param min the smallest value used for processing. After processing, all pixel values that are less than or equal to the Minimum in the original image are set to 0 for an 8-bit image. In 16-bit and floating-point images, these pixel values are set to the smallest pixel value found in the original image.
+* @param max the largest value used for processing. After processing, all pixel values that are greater than or equal to the Maximum in the original image are set to 255 for an 8-bit image. In 16-bit and floating-point images, these pixel values are set to the largest pixel value found in the original image.
+* @param mask an 8-bit image that specifies the region of the small image that will be copied. Only those pixels in the Image Src (Small) image that correspond to an equivalent non-zero pixel in the mask image are copied. All other pixels keep their original values. The entire image is processed if Image Mask is NULL or this parameter is omitted.
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*
+* option defaults:
+* searchRect = IMAQ_NO_RECT
+* minMatchScore = DEFAULT_MINMAX_SCORE (800)
+*/
+int frcEqualize(Image* dest, const Image* source, float min, float max)
+{ return frcEqualize(dest, source, min, max, NULL); }
+
+int frcEqualize(Image* dest, const Image* source, float min, float max, const Image* mask)
+{
+ return imaqEqualize(dest, source, min, max, mask);
+}
+
+/**
+* @brief Improves contrast on a color image.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL
+*
+* option defaults: colorEqualization = TRUE to equalize all three planes of the image
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+* @param dest The destination image.
+* @param source The image to equalize
+* @param colorEqualization Set this parameter to TRUE to equalize all three planes of the image (the default). Set this parameter to FALSE to equalize only the luminance plane.
+*/
+int frcColorEqualize(Image* dest, const Image* source)
+{
+ return imaqColorEqualize(dest, source, TRUE);
+}
+
+int frcColorEqualize(Image* dest, const Image* source, int colorEqualization)
+{
+ return imaqColorEqualize(dest, source, TRUE);
+}
+
+/* Image Conversion functions */
+
+/**
+* @brief Automatically thresholds a grayscale image into a binary image for Particle Analysis based on a smart threshold.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_I16
+* @param dest The destination image.
+* @param source The image to threshold
+* @param windowWidth The width of the rectangular window around the pixel on which the function
+* performs the local threshold. This number must be at least 3 and cannot be larger than the width of source
+* @param windowHeight The height of the rectangular window around the pixel on which the function
+* performs the local threshold. This number must be at least 3 and cannot be larger than the height of source
+* @param method Specifies the local thresholding method the function uses. Value can be IMAQ_NIBLACK
+* (which computes thresholds for each pixel based on its local statistics using the Niblack local thresholding
+* algorithm.), or IMAQ_BACKGROUND_CORRECTION (which does background correction first to eliminate non-uniform
+* lighting effects, then performs thresholding using the Otsu thresholding algorithm)
+* @param deviationWeight Specifies the k constant used in the Niblack local thresholding algorithm, which
+* determines the weight applied to the variance calculation. Valid k constants range from 0 to 1. Setting
+* this value to 0 will increase the performance of the function because the function will not calculate the
+* variance for any of the pixels. The function ignores this value if method is not set to IMAQ_NIBLACK
+* @param type Specifies the type of objects for which you want to look. Values can be IMAQ_BRIGHT_OBJECTS
+* or IMAQ_DARK_OBJECTS.
+* @param replaceValue Specifies the replacement value the function uses for the pixels of the kept objects
+* in the destination image.
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcSmartThreshold(Image* dest, const Image* source,
+ unsigned int windowWidth, unsigned int windowHeight, LocalThresholdMethod method,
+ double deviationWeight, ObjectType type)
+{
+ float replaceValue = 1.0;
+ return imaqLocalThreshold(dest, source, windowWidth, windowHeight, method,
+ deviationWeight, type, replaceValue);
+}
+
+int frcSmartThreshold(Image* dest, const Image* source,
+ unsigned int windowWidth, unsigned int windowHeight, LocalThresholdMethod method,
+ double deviationWeight, ObjectType type, float replaceValue)
+{
+ return imaqLocalThreshold(dest, source, windowWidth, windowHeight, method,
+ deviationWeight, type, replaceValue);
+}
+
+/**
+* @brief Converts a grayscale image to a binary image for Particle Analysis based on a fixed threshold.
+* The function sets pixels values outside of the given range to 0. The function sets pixel values
+* within the range to a given value or leaves the values unchanged.
+* Use the simplified call to leave pixel values unchanged.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_I16.
+*
+* @param dest The destination image.
+* @param source The image to threshold
+* @param rangeMin The lower boundary of the range of pixel values to keep
+* @param rangeMax The upper boundary of the range of pixel values to keep.
+*
+* @return int - error code: 0 = error. To get extended error information, call GetLastError().
+*/
+int frcSimpleThreshold(Image* dest, const Image* source, float rangeMin, float rangeMax)
+{
+ int newValue = 255;
+ return frcSimpleThreshold(dest, source, rangeMin, rangeMax, newValue);
+}
+
+/**
+* @brief Converts a grayscale image to a binary image for Particle Analysis based on a fixed threshold.
+* The function sets pixels values outside of the given range to 0. The function sets
+* pixel values within the range to the given value.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_I16.
+*
+* @param dest The destination image.
+* @param source The image to threshold
+* @param rangeMin The lower boundary of the range of pixel values to keep
+* @param rangeMax The upper boundary of the range of pixel values to keep.
+* @param newValue The replacement value for pixels within the range. Use the simplified call to leave the pixel values unchanged
+*
+* @return int - error code: 0 = error. To get extended error information, call GetLastError().
+*/
+int frcSimpleThreshold(Image* dest, const Image* source, float rangeMin, float rangeMax, float newValue)
+{
+ int useNewValue = TRUE;
+ return imaqThreshold(dest, source, rangeMin, rangeMax, useNewValue, newValue);
+}
+
+/**
+* @brief Applies a threshold to the Red, Green, and Blue values of a RGB image or the Hue,
+* Saturation, Luminance values for a HSL image.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL.
+* This simpler version filters based on a hue range in the HSL mode.
+*
+* @param dest The destination image. This must be a IMAQ_IMAGE_U8 image.
+* @param source The image to threshold
+* @param mode The color space to perform the threshold in. valid values are: IMAQ_RGB, IMAQ_HSL.
+* @param plane1Range The selection range for the first plane of the image. Set this parameter to NULL to use a selection range from 0 to 255.
+* @param plane2Range The selection range for the second plane of the image. Set this parameter to NULL to use a selection range from 0 to 255.
+* @param plane3Range The selection range for the third plane of the image. Set this parameter to NULL to use a selection range from 0 to 255.
+*
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+* */
+int frcColorThreshold(Image* dest, const Image* source, ColorMode mode,
+ const Range* plane1Range, const Range* plane2Range, const Range* plane3Range)
+{
+ int replaceValue = 1;
+ return imaqColorThreshold(dest, source, replaceValue, mode, plane1Range, plane2Range, plane3Range);
+}
+
+/**
+* @brief Applies a threshold to the Red, Green, and Blue values of a RGB image or the Hue,
+* Saturation, Luminance values for a HSL image.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL.
+* The simpler version filters based on a hue range in the HSL mode.
+*
+* @param dest The destination image. This must be a IMAQ_IMAGE_U8 image.
+* @param source The image to threshold
+* @param replaceValue Value to assign to selected pixels. Defaults to 1 if simplified call is used.
+* @param mode The color space to perform the threshold in. valid values are: IMAQ_RGB, IMAQ_HSL.
+* @param plane1Range The selection range for the first plane of the image. Set this parameter to NULL to use a selection range from 0 to 255.
+* @param plane2Range The selection range for the second plane of the image. Set this parameter to NULL to use a selection range from 0 to 255.
+* @param plane3Range The selection range for the third plane of the image. Set this parameter to NULL to use a selection range from 0 to 255.
+*
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcColorThreshold(Image* dest, const Image* source, int replaceValue, ColorMode mode,
+ const Range* plane1Range, const Range* plane2Range, const Range* plane3Range)
+{ return imaqColorThreshold(dest, source, replaceValue, mode, plane1Range, plane2Range, plane3Range);}
+
+
+/**
+* @brief A simpler version of ColorThreshold that thresholds hue range in the HSL mode. Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL.
+* @param dest The destination image.
+* @param source The image to threshold
+* @param hueRange The selection range for the hue (color).
+* @param minSaturation The minimum saturation value (1-255). If not used, DEFAULT_SATURATION_THRESHOLD is the default.
+*
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcHueThreshold(Image* dest, const Image* source, const Range* hueRange)
+{ return frcHueThreshold(dest, source, hueRange, DEFAULT_SATURATION_THRESHOLD); }
+
+int frcHueThreshold(Image* dest, const Image* source, const Range* hueRange, int minSaturation)
+{
+ // assume HSL mode
+ ColorMode mode = IMAQ_HSL;
+ // Set saturation 100 - 255
+ Range satRange; satRange.minValue = minSaturation; satRange.maxValue = 255;
+ // Set luminance 100 - 255
+ Range lumRange; lumRange.minValue = 100; lumRange.maxValue = 255;
+ // Replace pixels with 1 if pass threshold filter
+ int replaceValue = 1;
+ return imaqColorThreshold(dest, source, replaceValue, mode, hueRange, &satRange, &lumRange);
+}
+
+/**
+* @brief Extracts the Red, Green, Blue, or Hue, Saturation or Luminance information from a color image.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL, IMAQ_IMAGE_RGB_U64.
+*
+* @param image The source image that the function extracts the planes from.
+* @param mode The color space that the function extracts the planes from. Valid values are IMAQ_RGB, IMAQ_HSL, IMAQ_HSV, IMAQ_HSI.
+* @param plane1 On return, the first extracted plane. Set this parameter to NULL if you do not need this information. RGB-Red, HSL/HSV/HSI-Hue.
+* @param plane2 On return, the second extracted plane. Set this parameter to NULL if you do not need this information. RGB-Green, HSL/HSV/HSI-Saturation.
+* @param plane3 On return, the third extracted plane. Set this parameter to NULL if you do not need this information. RGB-Blue, HSL-Luminance, HSV-Value, HSI-Intensity.
+*
+* @return error code: 0 = error. To get extended error information, call GetLastError().
+*/
+int frcExtractColorPlanes(const Image* image, ColorMode mode,
+ Image* plane1, Image* plane2, Image* plane3)
+{ return imaqExtractColorPlanes(image, mode, plane1, plane2, plane3); }
+
+/**
+* @brief Extracts the Hue information from a color image. Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL, IMAQ_IMAGE_RGB_U64
+*
+* @param image The source image that the function extracts the plane from.
+* @param huePlane On return, the extracted hue plane.
+* @param minSaturation the minimum saturation level required 0-255 (try 50)
+*
+* @return On success: 1. On failure: 0. To get extended error information, call GetLastError().
+*/
+int frcExtractHuePlane(const Image* image, Image* huePlane)
+{
+ return frcExtractHuePlane(image, huePlane, DEFAULT_SATURATION_THRESHOLD);
+}
+
+int frcExtractHuePlane(const Image* image, Image* huePlane, int minSaturation)
+{
+ return frcExtractColorPlanes(image, IMAQ_HSL, huePlane, NULL, NULL);
+}
+
+
+
+
+
+
+
+
diff --git a/aos/externals/WPILib/WPILib/Vision2009/VisionAPI.h b/aos/externals/WPILib/WPILib/Vision2009/VisionAPI.h
new file mode 100644
index 0000000..31663f8
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Vision2009/VisionAPI.h
@@ -0,0 +1,163 @@
+/********************************************************************************
+* Project : FIRST Motor Controller
+* File Name : VisionAPI.h
+* Contributors : ELF, JDG, ARK, EMF
+* Creation Date : June 22, 2008
+* Revision History : Source code & revision history maintained at sourceforge.WPI.edu
+* File Description : Globally defined values for the FIRST Vision API
+*
+* API: Because nivision.h uses C++ style comments, any file including this
+* must be a .cpp (not .c).
+*/
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __VISIONAPI_H__
+#define __VISIONAPI_H__
+
+#include "nivision.h"
+
+/* Constants */
+
+#define DEFAULT_BORDER_SIZE 3 //VisionAPI.frcCreateImage
+#define DEFAULT_SATURATION_THRESHOLD 40 //TrackAPI.FindColor
+
+/* Forward Declare Data Structures */
+typedef struct FindEdgeOptions_struct FindEdgeOptions;
+typedef struct CircularEdgeReport_struct CircularEdgeReport;
+
+/* Data Structures */
+
+/** frcParticleAnalysis returns this structure */
+typedef struct ParticleAnalysisReport_struct {
+ int imageHeight;
+ int imageWidth;
+ double imageTimestamp;
+ int particleIndex; // the particle index analyzed
+ /* X-coordinate of the point representing the average position of the
+ * total particle mass, assuming every point in the particle has a constant density */
+ int center_mass_x; // MeasurementType: IMAQ_MT_CENTER_OF_MASS_X
+ /* Y-coordinate of the point representing the average position of the
+ * total particle mass, assuming every point in the particle has a constant density */
+ int center_mass_y; // MeasurementType: IMAQ_MT_CENTER_OF_MASS_Y
+ double center_mass_x_normalized; //Center of mass x value normalized to -1.0 to +1.0 range
+ double center_mass_y_normalized; //Center of mass y value normalized to -1.0 to +1.0 range
+ /* Area of the particle */
+ double particleArea; // MeasurementType: IMAQ_MT_AREA
+ /* Bounding Rectangle */
+ Rect boundingRect; // left/top/width/height
+ /* Percentage of the particle Area covering the Image Area. */
+ double particleToImagePercent; // MeasurementType: IMAQ_MT_AREA_BY_IMAGE_AREA
+ /* Percentage of the particle Area in relation to its Particle and Holes Area */
+ double particleQuality; // MeasurementType: IMAQ_MT_AREA_BY_PARTICLE_AND_HOLES_AREA
+} ParticleAnalysisReport;
+
+/** Tracking functions return this structure */
+typedef struct ColorReport_struct {
+ int numberParticlesFound; // Number of particles found for this color
+ int largestParticleNumber; // The particle index of the largest particle
+ /* Color information */
+ float particleHueMax; // HistogramReport: hue max
+ float particleHueMin; // HistogramReport: hue max
+ float particleHueMean; // HistogramReport: hue mean
+ float particleSatMax; // HistogramReport: saturation max
+ float particleSatMin; // HistogramReport: saturation max
+ float particleSatMean; // HistogramReport: saturation mean
+ float particleLumMax; // HistogramReport: luminance max
+ float particleLumMin; // HistogramReport: luminance max
+ float particleLumMean; // HistogramReport: luminance mean
+} ColorReport;
+
+
+/* Image Management functions */
+
+/* Create: calls imaqCreateImage. Border size is set to some default value */
+Image* frcCreateImage( ImageType type );
+
+/* Dispose: calls imaqDispose */
+int frcDispose( void* object );
+int frcDispose( const char* filename, ... ) ;
+
+/* Copy: calls imaqDuplicateImage */
+int frcCopyImage( Image* dest, const Image* source );
+
+/* Image Extraction: Crop: calls imaqScale */
+int frcCrop( Image* dest, const Image* source, Rect rect );
+
+/* Image Extraction: Scale: calls imaqScale. Scales entire image */
+int frcScale(Image* dest, const Image* source, int xScale, int yScale, ScalingMode scaleMode );
+
+/* Read Image : calls imaqReadFile */
+int frcReadImage( Image* image, const char* fileName );
+/* Write Image : calls imaqWriteFile */
+int frcWriteImage( const Image* image, const char* fileName);
+
+/* Measure Intensity functions */
+
+/* Histogram: calls imaqHistogram */
+HistogramReport* frcHistogram( const Image* image, int numClasses, float min, float max, Rect rect );
+/* Color Histogram: calls imaqColorHistogram2 */
+ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses, ColorMode mode, Image* mask);
+
+/* Get Pixel Value: calls imaqGetPixel */
+int frcGetPixelValue( const Image* image, Point pixel, PixelValue* value );
+
+/* Particle Analysis functions */
+
+/* Particle Filter: calls imaqParticleFilter3 */
+int frcParticleFilter(Image* dest, Image* source, const ParticleFilterCriteria2* criteria,
+ int criteriaCount, const ParticleFilterOptions* options, Rect rect, int* numParticles);
+int frcParticleFilter(Image* dest, Image* source, const ParticleFilterCriteria2* criteria,
+ int criteriaCount, const ParticleFilterOptions* options, int* numParticles);
+/* Morphology: calls imaqMorphology */
+int frcMorphology(Image* dest, Image* source, MorphologyMethod method);
+int frcMorphology(Image* dest, Image* source, MorphologyMethod method, const StructuringElement* structuringElement);
+/* Reject Border: calls imaqRejectBorder */
+int frcRejectBorder(Image* dest, Image* source);
+int frcRejectBorder(Image* dest, Image* source, int connectivity8);
+/* Count Particles: calls imaqCountParticles */
+int frcCountParticles(Image* image, int* numParticles);
+/* Particle Analysis Report: calls imaqMeasureParticle */
+int frcParticleAnalysis(Image* image, int particleNumber, ParticleAnalysisReport* par);
+
+/* Image Enhancement functions */
+
+/* Equalize: calls imaqEqualize */
+int frcEqualize(Image* dest, const Image* source, float min, float max);
+int frcEqualize(Image* dest, const Image* source, float min, float max, const Image* mask);
+
+/* Color Equalize: calls imaqColorEqualize */
+int frcColorEqualize(Image* dest, const Image* source);
+int frcColorEqualize(Image* dest, const Image* source, int colorEqualization);
+
+/* Image Thresholding & Conversion functions */
+
+/* Smart Threshold: calls imaqLocalThreshold */
+int frcSmartThreshold(Image* dest, const Image* source, unsigned int windowWidth, unsigned int windowHeight,
+ LocalThresholdMethod method, double deviationWeight, ObjectType type);
+int frcSmartThreshold(Image* dest, const Image* source, unsigned int windowWidth, unsigned int windowHeight,
+ LocalThresholdMethod method, double deviationWeight, ObjectType type, float replaceValue);
+
+/* Simple Threshold: calls imaqThreshold */
+int frcSimpleThreshold(Image* dest, const Image* source, float rangeMin, float rangeMax, float newValue);
+int frcSimpleThreshold(Image* dest, const Image* source, float rangeMin, float rangeMax);
+
+/* Color/Hue Threshold: calls imaqColorThreshold */
+int frcColorThreshold(Image* dest, const Image* source, ColorMode mode,
+ const Range* plane1Range, const Range* plane2Range, const Range* plane3Range);
+int frcColorThreshold(Image* dest, const Image* source, int replaceValue, ColorMode mode,
+ const Range* plane1Range, const Range* plane2Range, const Range* plane3Range);
+int frcHueThreshold(Image* dest, const Image* source, const Range* hueRange);
+int frcHueThreshold(Image* dest, const Image* source, const Range* hueRange, int minSaturation);
+
+/* Extract ColorHue Plane: calls imaqExtractColorPlanes */
+int frcExtractColorPlanes(const Image* image, ColorMode mode, Image* plane1, Image* plane2, Image* plane3);
+int frcExtractHuePlane(const Image* image, Image* huePlane);
+int frcExtractHuePlane(const Image* image, Image* huePlane, int minSaturation);
+
+#endif
+
+
diff --git a/aos/externals/WPILib/WPILib/WPIErrors.h b/aos/externals/WPILib/WPILib/WPIErrors.h
new file mode 100644
index 0000000..f7e59f5
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/WPIErrors.h
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __WPI_ERRORS_H__
+#define __WPI_ERRORS_H__
+
+#ifdef WPI_ERRORS_DEFINE_STRINGS
+#define S(label, offset, message) const char *wpi_error_s_##label = message ;
+#else
+#define S(label, offset, message) extern const char *wpi_error_s_##label;
+#endif
+
+/*
+ * Fatal errors
+ */
+S(ModuleIndexOutOfRange, -1, "Allocating module that is out of range or not found");
+S(ChannelIndexOutOfRange, -1, "Allocating channel that is out of range");
+S(NotAllocated, -2, "Attempting to free unallocated resource");
+S(ResourceAlreadyAllocated, -3, "Attempted to reuse an allocated resource");
+S(NoAvailableResources, -4, "No available resources to allocate");
+S(NullParameter, -5, "A pointer parameter to a method is NULL");
+S(Timeout, -6, "A timeout has been exceeded");
+S(CompassManufacturerError, -7, "Compass manufacturer doesn't match HiTechnic");
+S(CompassTypeError, -8, "Compass type doesn't match expected type for HiTechnic compass");
+S(IncompatibleMode, -9, "The object is in an incompatible mode");
+S(AnalogTriggerLimitOrderError, -10, "AnalogTrigger limits error. Lower limit > Upper Limit");
+S(AnalogTriggerPulseOutputError, -11, "Attempted to read AnalogTrigger pulse output.");
+S(TaskError, -12, "Task can't be started");
+S(TaskIDError, -13, "Task error: Invalid ID.");
+S(TaskDeletedError, -14, "Task error: Task already deleted.");
+S(TaskOptionsError, -15, "Task error: Invalid options.");
+S(TaskMemoryError, -16, "Task can't be started due to insufficient memory.");
+S(TaskPriorityError, -17, "Task error: Invalid priority [1-255].");
+S(DriveUninitialized, -18, "RobotDrive not initialized for the C interface");
+S(CompressorNonMatching, -19, "Compressor slot/channel doesn't match previous instance");
+S(CompressorAlreadyDefined, -20, "Creating a second compressor instance");
+S(CompressorUndefined, -21, "Using compressor functions without defining compressor");
+S(InconsistentArrayValueAdded, -22, "When packing data into an array to the dashboard, not all values added were of the same type.");
+S(MismatchedComplexTypeClose, -23, "When packing data to the dashboard, a Close for a complex type was called without a matching Open.");
+S(DashboardDataOverflow, -24, "When packing data to the dashboard, too much data was packed and the buffer overflowed.");
+S(DashboardDataCollision, -25, "The same buffer was used for packing data and for printing.");
+S(EnhancedIOMissing, -26, "IO is not attached or Enhanced IO is not enabled.");
+S(LineNotOutput, -27, "Cannot SetDigitalOutput for a line not configured for output.");
+S(ParameterOutOfRange, -28, "A parameter is out of range.");
+S(SPIClockRateTooLow, -29, "SPI clock rate was below the minimum supported");
+S(JaguarVersionError, -30, "Jaguar firmware version error");
+S(NetworkTablesReadError, -40, "Error reading NetworkTables socket");
+S(NetworkTablesBufferFull, -41, "Buffer full writing to NetworkTables socket");
+S(NetworkTablesWrongType, -42, "The wrong type was read from the NetworkTables entry");
+S(NetworkTablesCorrupt, -43, "NetworkTables data stream is corrupt");
+S(SmartDashboardMissingKey, -43, "SmartDashboard data does not exist");
+S(CommandIllegalUse, -50, "Illegal use of Command");
+
+/*
+ * Warnings
+ */
+S(SampleRateTooHigh, 1, "Analog module sample rate is too high");
+S(VoltageOutOfRange, 2, "Voltage to convert to raw value is out of range [-10; 10]");
+S(CompressorTaskError, 3, "Compressor task won't start");
+S(LoopTimingError, 4, "Digital module loop timing is not the expected value");
+S(NonBinaryDigitalValue, 5, "Digital output value is not 0 or 1");
+S(IncorrectBatteryChannel, 6, "Battery measurement channel is not correct value");
+S(BadJoystickIndex, 7, "Joystick index is out of range, should be 1-4");
+S(BadJoystickAxis, 8, "Joystick axis is out of range");
+S(InvalidMotorIndex, 9, "Motor index is out of range, should be 0-3");
+S(DriverStationTaskError, 10, "Driver Station task won't start");
+S(EnhancedIOPWMPeriodOutOfRange, 11, "Driver Station Enhanced IO PWM Output period out of range.");
+S(SPIWriteNoMOSI, 12, "Cannot write to SPI port with no MOSI output");
+S(SPIReadNoMISO, 13, "Cannot read from SPI port with no MISO input");
+S(SPIReadNoData, 14, "No data available to read from SPI");
+S(IncompatibleState, 15, "Incompatible State: The operation cannot be completed");
+
+#undef S
+
+#endif // __WPI_ERRORS_H__
diff --git a/aos/externals/WPILib/WPILib/WPILib.h b/aos/externals/WPILib/WPILib/WPILib.h
new file mode 100644
index 0000000..b1082cc
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/WPILib.h
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPILIB_H_
+#define WPILIB_H_
+
+#include "string.h"
+#include <iostream.h>
+
+#include "Accelerometer.h"
+#include "ADXL345_I2C.h"
+#include "ADXL345_SPI.h"
+#include "AnalogChannel.h"
+#include "AnalogModule.h"
+#include "AnalogTrigger.h"
+#include "AnalogTriggerOutput.h"
+#include "Buttons/AnalogIOButton.h"
+#include "Buttons/DigitalIOButton.h"
+#include "Buttons/InternalButton.h"
+#include "Buttons/JoystickButton.h"
+#include "Buttons/NetworkButton.h"
+#include "CANJaguar.h"
+#include "Commands/Command.h"
+#include "Commands/CommandGroup.h"
+#include "Commands/PIDCommand.h"
+#include "Commands/PIDSubsystem.h"
+#include "Commands/PrintCommand.h"
+#include "Commands/Scheduler.h"
+#include "Commands/StartCommand.h"
+#include "Commands/Subsystem.h"
+#include "Commands/WaitCommand.h"
+#include "Commands/WaitForChildren.h"
+#include "Commands/WaitUntilCommand.h"
+#include "Compressor.h"
+#include "Counter.h"
+#include "Dashboard.h"
+#include "DigitalInput.h"
+#include "DigitalModule.h"
+#include "DigitalOutput.h"
+#include "DigitalSource.h"
+#include "DoubleSolenoid.h"
+#include "DriverStation.h"
+#include "DriverStationEnhancedIO.h"
+#include "DriverStationLCD.h"
+#include "Encoder.h"
+#include "ErrorBase.h"
+#include "GearTooth.h"
+#include "GenericHID.h"
+#include "Gyro.h"
+#include "HiTechnicCompass.h"
+#include "I2C.h"
+#include "IterativeRobot.h"
+#include "InterruptableSensorBase.h"
+#include "Jaguar.h"
+#include "Joystick.h"
+#include "Kinect.h"
+#include "KinectStick.h"
+#include "NetworkTables/NetworkTable.h"
+#include "Notifier.h"
+#include "PIDController.h"
+#include "PIDOutput.h"
+#include "PIDSource.h"
+#include "Preferences.h"
+#include "PWM.h"
+#include "Relay.h"
+#include "Resource.h"
+#include "RobotBase.h"
+#include "RobotDrive.h"
+#include "SensorBase.h"
+#include "SerialPort.h"
+#include "Servo.h"
+#include "SimpleRobot.h"
+#include "SmartDashboard/SendableChooser.h"
+#include "SmartDashboard/SendableGyro.h"
+#include "SmartDashboard/SendablePIDController.h"
+#include "SmartDashboard/SmartDashboard.h"
+#include "Solenoid.h"
+#include "SpeedController.h"
+#include "SPI.h"
+#include "Synchronized.h"
+#include "Task.h"
+#include "Timer.h"
+#include "Ultrasonic.h"
+#include "Utility.h"
+#include "Victor.h"
+#include "Vision/AxisCamera.h"
+#include "Watchdog.h"
+#include "WPIErrors.h"
+
+#endif /*WPILIB_H_*/
diff --git a/aos/externals/WPILib/WPILib/Watchdog.cpp b/aos/externals/WPILib/WPILib/Watchdog.cpp
new file mode 100644
index 0000000..30a386e
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Watchdog.cpp
@@ -0,0 +1,170 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "Watchdog.h"
+
+const double Watchdog::kDefaultWatchdogExpiration;
+
+/**
+ * The Watchdog is born.
+ */
+Watchdog::Watchdog()
+ : m_fpgaWatchDog(NULL)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_fpgaWatchDog = tWatchdog::create(&localStatus);
+ wpi_setError(localStatus);
+ SetExpiration(kDefaultWatchdogExpiration);
+ SetEnabled(true);
+}
+
+/**
+ * Time to bury him in the back yard.
+ */
+Watchdog::~Watchdog()
+{
+ SetEnabled(false);
+ delete m_fpgaWatchDog;
+ m_fpgaWatchDog = NULL;
+}
+
+/**
+ * Throw the dog a bone.
+ *
+ * When everything is going well, you feed your dog when you get home.
+ * Let's hope you don't drive your car off a bridge on the way home...
+ * Your dog won't get fed and he will starve to death.
+ *
+ * By the way, it's not cool to ask the neighbor (some random task) to
+ * feed your dog for you. He's your responsibility!
+ *
+ * @returns Returns the previous state of the watchdog before feeding it.
+ */
+bool Watchdog::Feed()
+{
+ bool previous = GetEnabled();
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_fpgaWatchDog->strobeFeed(&localStatus);
+ wpi_setError(localStatus);
+ return previous;
+}
+
+/**
+ * Put the watchdog out of its misery.
+ *
+ * Don't wait for your dying robot to starve when there is a problem.
+ * Kill it quickly, cleanly, and humanely.
+ */
+void Watchdog::Kill()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_fpgaWatchDog->strobeKill(&localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Read how long it has been since the watchdog was last fed.
+ *
+ * @return The number of seconds since last meal.
+ */
+double Watchdog::GetTimer()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 timer = m_fpgaWatchDog->readTimer(&localStatus);
+ wpi_setError(localStatus);
+ return timer / (kSystemClockTicksPerMicrosecond * 1e6);
+}
+
+/**
+ * Read what the current expiration is.
+ *
+ * @return The number of seconds before starvation following a meal (watchdog starves if it doesn't eat this often).
+ */
+double Watchdog::GetExpiration()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ UINT32 expiration = m_fpgaWatchDog->readExpiration(&localStatus);
+ wpi_setError(localStatus);
+ return expiration / (kSystemClockTicksPerMicrosecond * 1e6);
+}
+
+/**
+ * Configure how many seconds your watchdog can be neglected before it starves to death.
+ *
+ * @param expiration The number of seconds before starvation following a meal (watchdog starves if it doesn't eat this often).
+ */
+void Watchdog::SetExpiration(double expiration)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_fpgaWatchDog->writeExpiration((UINT32)(expiration * (kSystemClockTicksPerMicrosecond * 1e6)), &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Find out if the watchdog is currently enabled or disabled (mortal or immortal).
+ *
+ * @return Enabled or disabled.
+ */
+bool Watchdog::GetEnabled()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool enabled = !m_fpgaWatchDog->readImmortal(&localStatus);
+ wpi_setError(localStatus);
+ return enabled;
+}
+
+/**
+ * Enable or disable the watchdog timer.
+ *
+ * When enabled, you must keep feeding the watchdog timer to
+ * keep the watchdog active, and hence the dangerous parts
+ * (motor outputs, etc.) can keep functioning.
+ * When disabled, the watchdog is immortal and will remain active
+ * even without being fed. It will also ignore any kill commands
+ * while disabled.
+ *
+ * @param enabled Enable or disable the watchdog.
+ */
+void Watchdog::SetEnabled(bool enabled)
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ m_fpgaWatchDog->writeImmortal(!enabled, &localStatus);
+ wpi_setError(localStatus);
+}
+
+/**
+ * Check in on the watchdog and make sure he's still kicking.
+ *
+ * This indicates that your watchdog is allowing the system to operate.
+ * It is still possible that the network communications is not allowing the
+ * system to run, but you can check this to make sure it's not your fault.
+ * Check IsSystemActive() for overall system status.
+ *
+ * If the watchdog is disabled, then your watchdog is immortal.
+ *
+ * @return Is the watchdog still alive?
+ */
+bool Watchdog::IsAlive()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool alive = m_fpgaWatchDog->readStatus_Alive(&localStatus);
+ wpi_setError(localStatus);
+ return alive;
+}
+
+/**
+ * Check on the overall status of the system.
+ *
+ * @return Is the system active (i.e. PWM motor outputs, etc. enabled)?
+ */
+bool Watchdog::IsSystemActive()
+{
+ tRioStatusCode localStatus = NiFpga_Status_Success;
+ bool alive = m_fpgaWatchDog->readStatus_SystemActive(&localStatus);
+ wpi_setError(localStatus);
+ return alive;
+}
+
diff --git a/aos/externals/WPILib/WPILib/Watchdog.h b/aos/externals/WPILib/WPILib/Watchdog.h
new file mode 100644
index 0000000..b7e35da
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/Watchdog.h
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WATCHDOG_H
+#define WATCHDOG_H
+
+#include "ChipObject.h"
+#include "SensorBase.h"
+#include "Base.h"
+
+/**
+ * Watchdog timer class.
+ * The watchdog timer is designed to keep the robots safe. The idea is that the robot program must
+ * constantly "feed" the watchdog otherwise it will shut down all the motor outputs. That way if a
+ * program breaks, rather than having the robot continue to operate at the last known speed, the
+ * motors will be shut down.
+ *
+ * This is serious business. Don't just disable the watchdog. You can't afford it!
+ *
+ * http://thedailywtf.com/Articles/_0x2f__0x2f_TODO_0x3a__Uncomment_Later.aspx
+ */
+class Watchdog : public SensorBase
+{
+public:
+ static const double kDefaultWatchdogExpiration = 0.5;
+
+ Watchdog();
+ virtual ~Watchdog();
+ bool Feed();
+ void Kill();
+ double GetTimer();
+ double GetExpiration();
+ void SetExpiration(double expiration);
+ bool GetEnabled();
+ void SetEnabled(bool enabled);
+ bool IsAlive();
+ bool IsSystemActive();
+
+private:
+ tWatchdog *m_fpgaWatchDog;
+ DISALLOW_COPY_AND_ASSIGN(Watchdog);
+};
+
+#endif
diff --git a/aos/externals/WPILib/WPILib/nivision.h b/aos/externals/WPILib/WPILib/nivision.h
new file mode 100644
index 0000000..14de95d
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/nivision.h
@@ -0,0 +1,5343 @@
+/*============================================================================*/
+/* IMAQ Vision */
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) National Instruments 2001. All Rights Reserved. */
+/*----------------------------------------------------------------------------*/
+/* */
+/* Title: NIVision.h */
+/* */
+/*============================================================================*/
+#if !defined(NiVision_h)
+#define NiVision_h
+
+//============================================================================
+// Includes
+//============================================================================
+#include <stddef.h>
+
+
+//============================================================================
+// Control Defines
+//============================================================================
+#if !defined(IMAQ_IMPORT)
+ #ifndef __GNUC__
+ #define IMAQ_IMPORT __declspec(dllimport)
+ #else
+ #define IMAQ_IMPORT
+ #endif
+#endif
+
+#if !defined(IMAQ_FUNC)
+ #if !defined(__cplusplus)
+ #define IMAQ_FUNC IMAQ_IMPORT
+ #else
+ #define IMAQ_FUNC extern "C" IMAQ_IMPORT
+ #endif
+#endif
+
+#if !defined(IMAQ_STDCALL)
+ #ifndef __GNUC__
+ #define IMAQ_STDCALL __stdcall
+ #else
+ #define IMAQ_STDCALL
+ #endif
+#endif
+
+#ifdef _CVI_
+#pragma EnableLibraryRuntimeChecking
+#include <ansi_c.h>
+#endif
+
+#define IMAQ_CALLBACK __cdecl
+
+//============================================================================
+// Manifest Constants
+//============================================================================
+#ifndef NULL
+ #ifdef __cplusplus
+ #define NULL 0
+ #else
+ #define NULL ((void *)0)
+ #endif
+#endif
+
+#ifndef FALSE
+ #define FALSE 0
+#endif
+
+#ifndef TRUE
+ #define TRUE 1
+#endif
+
+#define IMAQ_DEFAULT_SHOW_COORDINATES TRUE
+#define IMAQ_DEFAULT_MAX_ICONS_PER_LINE 4
+#define IMAQ_DEFAULT_LEARNING_MODE IMAQ_LEARN_SHIFT_INFORMATION
+#define IMAQ_DEFAULT_BMP_COMPRESS FALSE
+#define IMAQ_DEFAULT_PNG_QUALITY 750
+#define IMAQ_DEFAULT_JPEG_QUALITY 750
+#define IMAQ_ALL_CONTOURS -1
+#define IMAQ_ALL_WINDOWS -1
+#define IMAQ_SHIFT 1
+#define IMAQ_ALT 2
+#define IMAQ_CTRL 4
+#define IMAQ_CAPS_LOCK 8
+#define IMAQ_MODAL_DIALOG -1
+#define IMAQ_INIT_RGB_TRANSPARENT { 0, 0, 0, 1 }
+#define IMAQ_INIT_RGB_RED { 0, 0, 255, 0 }
+#define IMAQ_INIT_RGB_BLUE { 255, 0, 0, 0 }
+#define IMAQ_INIT_RGB_GREEN { 0, 255, 0, 0 }
+#define IMAQ_INIT_RGB_YELLOW { 0, 255, 255, 0 }
+#define IMAQ_INIT_RGB_WHITE { 255, 255, 255, 0 }
+#define IMAQ_INIT_RGB_BLACK { 0, 0, 0, 0 }
+#define IMAQ_USE_DEFAULT_QUALITY -1
+#define IMAQ_ALL_SAMPLES -1
+#define IMAQ_ALL_OBJECTS -1
+#define IMAQ_ALL_CHARACTERS -1
+
+//============================================================================
+// Predefined Valid Characters
+//============================================================================
+#define IMAQ_ANY_CHARACTER "" //Any Character
+#define IMAQ_ALPHABETIC "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz" //Alphabetic
+#define IMAQ_ALPHANUMERIC "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789" //Alphanumeric
+#define IMAQ_UPPERCASE_LETTERS "ABCDEFGHIJKLMNOPQRSTUVWXYZ" //Uppercase Letters
+#define IMAQ_LOWERCASE_LETTERS "abcdefghijklmnopqrstuvwxyz" //Lowercase Letters
+#define IMAQ_DECIMAL_DIGITS "0123456789" //Decimal Digits
+#define IMAQ_HEXADECIMAL_DIGITS "0123456789ABCDEFabcdef" //Hexadecimal Digits
+#define IMAQ_PATTERN "\xFF" //Pattern (A single character string with the character value set to 255)
+#define IMAQ_FORCE_SPACE " " //Force Space
+
+//============================================================================
+// Macros
+//============================================================================
+#define IMAQ_NO_RECT imaqMakeRect( 0, 0, 0x7FFFFFFF, 0x7FFFFFFF)
+#define IMAQ_NO_ROTATED_RECT imaqMakeRotatedRect( 0, 0, 0x7FFFFFFF, 0x7FFFFFFF, 0)
+#define IMAQ_NO_POINT imaqMakePoint( -1, -1)
+#define IMAQ_NO_POINT_FLOAT imaqMakePointFloat( -1.0, -1.0 )
+#define IMAQ_NO_OFFSET imaqMakePointFloat( 0.0, 0.0 )
+
+
+
+//============================================================================
+// When in Borland, some functions must be mapped to different names.
+// This accomplishes said task.
+//============================================================================
+#if defined(__BORLANDC__) || (defined(_CVI_) && defined(_NI_BC_))
+ #define imaqMakePoint imaqMakePoint_BC
+ #define imaqMakePointFloat imaqMakePointFloat_BC
+#endif
+
+
+//============================================================================
+// When in Watcom, some functions must be mapped to different names.
+// This accomplishes said task.
+//============================================================================
+#if defined(__WATCOMC__) || (defined(_CVI_) && defined(_NI_WC_))
+ #define imaqMakePoint imaqMakePoint_BC
+ #define imaqMakePointFloat imaqMakePointFloat_BC
+#endif
+
+//============================================================================
+// If using Visual C++, force startup & shutdown code to run.
+//============================================================================
+#if defined(_MSC_VER) && !defined(_CVI_) && !defined(__BORLANDC__)
+ #pragma comment(linker, "/INCLUDE:_nivision_startup_shutdown")
+ #pragma comment(linker, "/DEFAULTLIB:nivision.lib")
+#endif
+
+//============================================================================
+// Error Codes
+//============================================================================
+#define ERR_SUCCESS 0 // No error.
+#define ERR_SYSTEM_ERROR -1074396160 // System error.
+#define ERR_OUT_OF_MEMORY -1074396159 // Not enough memory for requested operation.
+#define ERR_MEMORY_ERROR -1074396158 // Memory error.
+#define ERR_UNREGISTERED -1074396157 // Unlicensed copy of NI Vision.
+#define ERR_NEED_FULL_VERSION -1074396156 // The function requires an NI Vision 5.0 Advanced license.
+#define ERR_UNINIT -1074396155 // NI Vision did not initialize properly.
+#define ERR_IMAGE_TOO_SMALL -1074396154 // The image is not large enough for the operation.
+#define ERR_BARCODE_CODABAR -1074396153 // The barcode is not a valid Codabar barcode.
+#define ERR_BARCODE_CODE39 -1074396152 // The barcode is not a valid Code 3 of 9 barcode.
+#define ERR_BARCODE_CODE93 -1074396151 // The barcode is not a valid Code93 barcode.
+#define ERR_BARCODE_CODE128 -1074396150 // The barcode is not a valid Code128 barcode.
+#define ERR_BARCODE_EAN8 -1074396149 // The barcode is not a valid EAN8 barcode.
+#define ERR_BARCODE_EAN13 -1074396148 // The barcode is not a valid EAN13 barcode.
+#define ERR_BARCODE_I25 -1074396147 // The barcode is not a valid Interleaved 2 of 5 barcode.
+#define ERR_BARCODE_MSI -1074396146 // The barcode is not a valid MSI barcode.
+#define ERR_BARCODE_UPCA -1074396145 // The barcode is not a valid UPCA barcode.
+#define ERR_BARCODE_CODE93_SHIFT -1074396144 // The Code93 barcode contains invalid shift encoding.
+#define ERR_BARCODE_TYPE -1074396143 // The barcode type is invalid.
+#define ERR_BARCODE_INVALID -1074396142 // The image does not represent a valid linear barcode.
+#define ERR_BARCODE_CODE128_FNC -1074396141 // The FNC value in the Code128 barcode is not located before the first data value.
+#define ERR_BARCODE_CODE128_SET -1074396140 // The starting code set in the Code128 barcode is not valid.
+#define ERR_ROLLBACK_RESOURCE_OUT_OF_MEMORY -1074396139 // Not enough reserved memory in the timed environment for the requested operation.
+#define ERR_ROLLBACK_NOT_SUPPORTED -1074396138 // The function is not supported when a time limit is active.
+#define ERR_DIRECTX_DLL_NOT_FOUND -1074396137 // Quartz.dll not found. Install DirectX 8.1 or later.
+#define ERR_DIRECTX_INVALID_FILTER_QUALITY -1074396136 // The filter quality you provided is invalid. Valid quality values range from -1 to 1000.
+#define ERR_INVALID_BUTTON_LABEL -1074396135 // Invalid button label.
+#define ERR_THREAD_INITIALIZING -1074396134 // Could not execute the function in the separate thread because the thread has not completed initialization.
+#define ERR_THREAD_COULD_NOT_INITIALIZE -1074396133 // Could not execute the function in the separate thread because the thread could not initialize.
+#define ERR_MASK_NOT_TEMPLATE_SIZE -1074396132 // The mask must be the same size as the template.
+#define ERR_NOT_RECT_OR_ROTATED_RECT -1074396130 // The ROI must only have either a single Rectangle contour or a single Rotated Rectangle contour.
+#define ERR_ROLLBACK_UNBOUNDED_INTERFACE -1074396129 // During timed execution, you must use the preallocated version of this operation.
+#define ERR_ROLLBACK_RESOURCE_CONFLICT_3 -1074396128 // An image being modified by one process cannot be requested by another process while a time limit is active.
+#define ERR_ROLLBACK_RESOURCE_CONFLICT_2 -1074396127 // An image with pattern matching, calibration, or overlay information cannot be manipulated while a time limit is active.
+#define ERR_ROLLBACK_RESOURCE_CONFLICT_1 -1074396126 // An image created before a time limit is started cannot be resized while a time limit is active.
+#define ERR_INVALID_CONTRAST_THRESHOLD -1074396125 // Invalid contrast threshold. The threshold value must be greater than 0.
+#define ERR_INVALID_CALIBRATION_ROI_MODE -1074396124 // NI Vision does not support the calibration ROI mode you supplied.
+#define ERR_INVALID_CALIBRATION_MODE -1074396123 // NI Vision does not support the calibration mode you supplied.
+#define ERR_DRAWTEXT_COLOR_MUST_BE_GRAYSCALE -1074396122 // Set the foreground and background text colors to grayscale to draw on a U8 image.
+#define ERR_SATURATION_THRESHOLD_OUT_OF_RANGE -1074396121 // The value of the saturation threshold must be from 0 to 255.
+#define ERR_NOT_IMAGE -1074396120 // Not an image.
+#define ERR_CUSTOMDATA_INVALID_KEY -1074396119 // They custom data key you supplied is invalid. The only valid character values are decimal 32-126 and 161-255. There must also be no repeated, leading, or trailing spaces.
+#define ERR_INVALID_STEP_SIZE -1074396118 // Step size must be greater than zero and less than Image size
+#define ERR_MATRIX_SIZE -1074396117 // Invalid matrix size in the structuring element.
+#define ERR_CALIBRATION_INSF_POINTS -1074396116 // Insufficient number of calibration feature points.
+#define ERR_CALIBRATION_IMAGE_CORRECTED -1074396115 // The operation is invalid in a corrected image.
+#define ERR_CALIBRATION_INVALID_ROI -1074396114 // The ROI contains an invalid contour type or is not contained in the ROI learned for calibration.
+#define ERR_CALIBRATION_IMAGE_UNCALIBRATED -1074396113 // The source/input image has not been calibrated.
+#define ERR_INCOMP_MATRIX_SIZE -1074396112 // The number of pixel and real-world coordinates must be equal.
+#define ERR_CALIBRATION_FAILED_TO_FIND_GRID -1074396111 // Unable to automatically detect grid because the image is too distorted.
+#define ERR_CALIBRATION_INFO_VERSION -1074396110 // Invalid calibration information version.
+#define ERR_CALIBRATION_INVALID_SCALING_FACTOR -1074396109 // Invalid calibration scaling factor.
+#define ERR_CALIBRATION_ERRORMAP -1074396108 // The calibration error map cannot be computed.
+#define ERR_CALIBRATION_INFO_1 -1074396107 // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_2 -1074396106 // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_3 -1074396105 // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_4 -1074396104 // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_5 -1074396103 // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_6 -1074396102 // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_MICRO_PLANE -1074396101 // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_PERSPECTIVE_PROJECTION -1074396100 // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_SIMPLE_TRANSFORM -1074396099 // Invalid calibration template image.
+#define ERR_RESERVED_MUST_BE_NULL -1074396098 // You must pass NULL for the reserved parameter.
+#define ERR_INVALID_PARTICLE_PARAMETER_VALUE -1074396097 // You entered an invalid selection in the particle parameter.
+#define ERR_NOT_AN_OBJECT -1074396096 // Not an object.
+#define ERR_CALIBRATION_DUPLICATE_REFERENCE_POINT -1074396095 // The reference points passed are inconsistent. At least two similar pixel coordinates correspond to different real-world coordinates.
+#define ERR_ROLLBACK_RESOURCE_CANNOT_UNLOCK -1074396094 // A resource conflict occurred in the timed environment. Two processes cannot manage the same resource and be time bounded.
+#define ERR_ROLLBACK_RESOURCE_LOCKED -1074396093 // A resource conflict occurred in the timed environment. Two processes cannot access the same resource and be time bounded.
+#define ERR_ROLLBACK_RESOURCE_NON_EMPTY_INITIALIZE -1074396092 // Multiple timed environments are not supported.
+#define ERR_ROLLBACK_RESOURCE_UNINITIALIZED_ENABLE -1074396091 // A time limit cannot be started until the timed environment is initialized.
+#define ERR_ROLLBACK_RESOURCE_ENABLED -1074396090 // Multiple timed environments are not supported.
+#define ERR_ROLLBACK_RESOURCE_REINITIALIZE -1074396089 // The timed environment is already initialized.
+#define ERR_ROLLBACK_RESIZE -1074396088 // The results of the operation exceeded the size limits on the output data arrays.
+#define ERR_ROLLBACK_STOP_TIMER -1074396087 // No time limit is available to stop.
+#define ERR_ROLLBACK_START_TIMER -1074396086 // A time limit could not be set.
+#define ERR_ROLLBACK_INIT_TIMER -1074396085 // The timed environment could not be initialized.
+#define ERR_ROLLBACK_DELETE_TIMER -1074396084 // No initialized timed environment is available to close.
+#define ERR_ROLLBACK_TIMEOUT -1074396083 // The time limit has expired.
+#define ERR_PALETTE_NOT_SUPPORTED -1074396082 // Only 8-bit images support the use of palettes. Either do not use a palette, or convert your image to an 8-bit image before using a palette.
+#define ERR_BAD_PASSWORD -1074396081 // Incorrect password.
+#define ERR_INVALID_IMAGE_TYPE -1074396080 // Invalid image type.
+#define ERR_INVALID_METAFILE_HANDLE -1074396079 // Invalid metafile handle.
+#define ERR_INCOMP_TYPE -1074396077 // Incompatible image type.
+#define ERR_COORD_SYS_FIRST_AXIS -1074396076 // Unable to fit a line for the primary axis.
+#define ERR_COORD_SYS_SECOND_AXIS -1074396075 // Unable to fit a line for the secondary axis.
+#define ERR_INCOMP_SIZE -1074396074 // Incompatible image size.
+#define ERR_MASK_OUTSIDE_IMAGE -1074396073 // When the mask's offset was applied, the mask was entirely outside of the image.
+#define ERR_INVALID_BORDER -1074396072 // Invalid image border.
+#define ERR_INVALID_SCAN_DIRECTION -1074396071 // Invalid scan direction.
+#define ERR_INVALID_FUNCTION -1074396070 // Unsupported function.
+#define ERR_INVALID_COLOR_MODE -1074396069 // NI Vision does not support the color mode you specified.
+#define ERR_INVALID_ACTION -1074396068 // The function does not support the requested action.
+#define ERR_IMAGES_NOT_DIFF -1074396067 // The source image and destination image must be different.
+#define ERR_INVALID_POINTSYMBOL -1074396066 // Invalid point symbol.
+#define ERR_CANT_RESIZE_EXTERNAL -1074396065 // Cannot resize an image in an acquisition buffer.
+#define ERR_EXTERNAL_NOT_SUPPORTED -1074396064 // This operation is not supported for images in an acquisition buffer.
+#define ERR_EXTERNAL_ALIGNMENT -1074396063 // The external buffer must be aligned on a 4-byte boundary. The line width and border pixels must be 4-byte aligned, as well.
+#define ERR_INVALID_TOLERANCE -1074396062 // The tolerance parameter must be greater than or equal to 0.
+#define ERR_INVALID_WINDOW_SIZE -1074396061 // The size of each dimension of the window must be greater than 2 and less than or equal to the size of the image in the corresponding dimension.
+#define ERR_JPEG2000_LOSSLESS_WITH_FLOATING_POINT -1074396060 // Lossless compression cannot be used with the floating point wavelet transform mode. Either set the wavelet transform mode to integer, or use lossy compression.
+#define ERR_INVALID_MAX_ITERATIONS -1074396059 // Invalid maximum number of iterations. Maximum number of iterations must be greater than zero.
+#define ERR_INVALID_ROTATION_MODE -1074396058 // Invalid rotation mode.
+#define ERR_INVALID_SEARCH_VECTOR_WIDTH -1074396057 // Invalid search vector width. The width must be an odd number greater than zero.
+#define ERR_INVALID_MATRIX_MIRROR_MODE -1074396056 // Invalid matrix mirror mode.
+#define ERR_INVALID_ASPECT_RATIO -1074396055 // Invalid aspect ratio. Valid aspect ratios must be greater than or equal to zero.
+#define ERR_INVALID_CELL_FILL_TYPE -1074396054 // Invalid cell fill type.
+#define ERR_INVALID_BORDER_INTEGRITY -1074396053 // Invalid border integrity. Valid values range from 0 to 100.
+#define ERR_INVALID_DEMODULATION_MODE -1074396052 // Invalid demodulation mode.
+#define ERR_INVALID_CELL_FILTER_MODE -1074396051 // Invalid cell filter mode.
+#define ERR_INVALID_ECC_TYPE -1074396050 // Invalid ECC type.
+#define ERR_INVALID_MATRIX_POLARITY -1074396049 // Invalid matrix polarity.
+#define ERR_INVALID_CELL_SAMPLE_SIZE -1074396048 // Invalid cell sample size.
+#define ERR_INVALID_LINEAR_AVERAGE_MODE -1074396047 // Invalid linear average mode.
+#define ERR_INVALID_2D_BARCODE_CONTRAST_FOR_ROI -1074396046 // When using a region of interest that is not a rectangle, you must specify the contrast mode of the barcode as either black on white or white on black.
+#define ERR_INVALID_2D_BARCODE_SUBTYPE -1074396045 // Invalid 2-D barcode Data Matrix subtype.
+#define ERR_INVALID_2D_BARCODE_SHAPE -1074396044 // Invalid 2-D barcode shape.
+#define ERR_INVALID_2D_BARCODE_CELL_SHAPE -1074396043 // Invalid 2-D barcode cell shape.
+#define ERR_INVALID_2D_BARCODE_CONTRAST -1074396042 // Invalid 2-D barcode contrast.
+#define ERR_INVALID_2D_BARCODE_TYPE -1074396041 // Invalid 2-D barcode type.
+#define ERR_DRIVER -1074396040 // Cannot access NI-IMAQ driver.
+#define ERR_IO_ERROR -1074396039 // I/O error.
+#define ERR_FIND_COORDSYS_MORE_THAN_ONE_EDGE -1074396038 // When searching for a coordinate system, the number of lines to fit must be 1.
+#define ERR_TIMEOUT -1074396037 // Trigger timeout.
+#define ERR_INVALID_SKELETONMODE -1074396036 // The Skeleton mode you specified is invalid.
+#define ERR_TEMPLATEIMAGE_NOCIRCLE -1074396035 // The template image does not contain enough information for learning the aggressive search strategy.
+#define ERR_TEMPLATEIMAGE_EDGEINFO -1074396034 // The template image does not contain enough edge information for the sample size(s) requested.
+#define ERR_TEMPLATEDESCRIPTOR_LEARNSETUPDATA -1074396033 // Invalid template descriptor.
+#define ERR_TEMPLATEDESCRIPTOR_ROTATION_SEARCHSTRATEGY -1074396032 // The template descriptor does not contain data required for the requested search strategy in rotation-invariant matching.
+#define ERR_INVALID_TETRAGON -1074396031 // The input tetragon must have four points. The points are specified clockwise starting with the top left point.
+#define ERR_TOO_MANY_CLASSIFICATION_SESSIONS -1074396030 // There are too many classification sessions open. You must close a session before you can open another one.
+#define ERR_TIME_BOUNDED_EXECUTION_NOT_SUPPORTED -1074396028 // NI Vision no longer supports time-bounded execution.
+#define ERR_INVALID_COLOR_RESOLUTION -1074396027 // Invalid Color Resolution for the Color Classifier
+#define ERR_INVALID_PROCESS_TYPE_FOR_EDGE_DETECTION -1074396026 // Invalid process type for edge detection.
+#define ERR_INVALID_ANGLE_RANGE_FOR_STRAIGHT_EDGE -1074396025 // Angle range value should be equal to or greater than zero.
+#define ERR_INVALID_MIN_COVERAGE_FOR_STRAIGHT_EDGE -1074396024 // Minimum coverage value should be greater than zero.
+#define ERR_INVALID_ANGLE_TOL_FOR_STRAIGHT_EDGE -1074396023 // The angle tolerance should be equal to or greater than 0.001.
+#define ERR_INVALID_SEARCH_MODE_FOR_STRAIGHT_EDGE -1074396022 // Invalid search mode for detecting straight edges
+#define ERR_INVALID_KERNEL_SIZE_FOR_EDGE_DETECTION -1074396021 // Invalid kernel size for edge detection. The minimum kernel size is 3, the maximum kernel size is 1073741823 and the kernel size must be odd.
+#define ERR_INVALID_GRADING_MODE -1074396020 // Invalid grading mode.
+#define ERR_INVALID_THRESHOLD_PERCENTAGE -1074396019 // Invalid threshold percentage. Valid values range from 0 to 100.
+#define ERR_INVALID_EDGE_POLARITY_SEARCH_MODE -1074396018 // Invalid edge polarity search mode.
+#define ERR_OPENING_NEWER_AIM_GRADING_DATA -1074396017 // The AIM grading data attached to the image you tried to open was created with a newer version of NI Vision. Upgrade to the latest version of NI Vision to read this file.
+#define ERR_NO_VIDEO_DRIVER -1074396016 // No video driver is installed.
+#define ERR_RPC_EXECUTE_IVB -1074396015 // Unable to establish network connection with remote system.
+#define ERR_INVALID_VIDEO_BLIT -1074396014 // RT Video Out does not support displaying the supplied image type at the selected color depth.
+#define ERR_INVALID_VIDEO_MODE -1074396013 // Invalid video mode.
+#define ERR_RPC_EXECUTE -1074396012 // Unable to display remote image on network connection.
+#define ERR_RPC_BIND -1074396011 // Unable to establish network connection.
+#define ERR_INVALID_FRAME_NUMBER -1074396010 // Invalid frame number.
+#define ERR_DIRECTX -1074396009 // An internal DirectX error has occurred. Try upgrading to the latest version of DirectX.
+#define ERR_DIRECTX_NO_FILTER -1074396008 // An appropriate DirectX filter to process this file could not be found. Install the filter that was used to create this AVI. Upgrading to the latest version of DirectX may correct this error. NI Vision requires DirectX 8.1 or higher.
+#define ERR_DIRECTX_INCOMPATIBLE_COMPRESSION_FILTER -1074396007 // Incompatible compression filter.
+#define ERR_DIRECTX_UNKNOWN_COMPRESSION_FILTER -1074396006 // Unknown compression filter.
+#define ERR_INVALID_AVI_SESSION -1074396005 // Invalid AVI session.
+#define ERR_DIRECTX_CERTIFICATION_FAILURE -1074396004 // A software key is restricting the use of this compression filter.
+#define ERR_AVI_DATA_EXCEEDS_BUFFER_SIZE -1074396003 // The data for this frame exceeds the data buffer size specified when creating the AVI file.
+#define ERR_INVALID_LINEGAUGEMETHOD -1074396002 // Invalid line gauge method.
+#define ERR_TOO_MANY_AVI_SESSIONS -1074396001 // There are too many AVI sessions open. You must close a session before you can open another one.
+#define ERR_FILE_FILE_HEADER -1074396000 // Invalid file header.
+#define ERR_FILE_FILE_TYPE -1074395999 // Invalid file type.
+#define ERR_FILE_COLOR_TABLE -1074395998 // Invalid color table.
+#define ERR_FILE_ARGERR -1074395997 // Invalid parameter.
+#define ERR_FILE_OPEN -1074395996 // File is already open for writing.
+#define ERR_FILE_NOT_FOUND -1074395995 // File not found.
+#define ERR_FILE_TOO_MANY_OPEN -1074395994 // Too many files open.
+#define ERR_FILE_IO_ERR -1074395993 // File I/O error.
+#define ERR_FILE_PERMISSION -1074395992 // File access denied.
+#define ERR_FILE_INVALID_TYPE -1074395991 // NI Vision does not support the file type you specified.
+#define ERR_FILE_GET_INFO -1074395990 // Could not read Vision info from file.
+#define ERR_FILE_READ -1074395989 // Unable to read data.
+#define ERR_FILE_WRITE -1074395988 // Unable to write data.
+#define ERR_FILE_EOF -1074395987 // Premature end of file.
+#define ERR_FILE_FORMAT -1074395986 // Invalid file format.
+#define ERR_FILE_OPERATION -1074395985 // Invalid file operation.
+#define ERR_FILE_INVALID_DATA_TYPE -1074395984 // NI Vision does not support the file data type you specified.
+#define ERR_FILE_NO_SPACE -1074395983 // Disk full.
+#define ERR_INVALID_FRAMES_PER_SECOND -1074395982 // The frames per second in an AVI must be greater than zero.
+#define ERR_INSUFFICIENT_BUFFER_SIZE -1074395981 // The buffer that was passed in is not big enough to hold all of the data.
+#define ERR_COM_INITIALIZE -1074395980 // Error initializing COM.
+#define ERR_INVALID_PARTICLE_INFO -1074395979 // The image has invalid particle information. Call imaqCountParticles on the image to create particle information.
+#define ERR_INVALID_PARTICLE_NUMBER -1074395978 // Invalid particle number.
+#define ERR_AVI_VERSION -1074395977 // The AVI file was created in a newer version of NI Vision. Upgrade to the latest version of NI Vision to read this AVI file.
+#define ERR_NUMBER_OF_PALETTE_COLORS -1074395976 // The color palette must have exactly 0 or 256 entries.
+#define ERR_AVI_TIMEOUT -1074395975 // DirectX has timed out reading or writing the AVI file. When closing an AVI file, try adding an additional delay. When reading an AVI file, try reducing CPU and disk load.
+#define ERR_UNSUPPORTED_JPEG2000_COLORSPACE_METHOD -1074395974 // NI Vision does not support reading JPEG2000 files with this colorspace method.
+#define ERR_JPEG2000_UNSUPPORTED_MULTIPLE_LAYERS -1074395973 // NI Vision does not support reading JPEG2000 files with more than one layer.
+#define ERR_DIRECTX_ENUMERATE_FILTERS -1074395972 // DirectX is unable to enumerate the compression filters. This is caused by a third-party compression filter that is either improperly installed or is preventing itself from being enumerated. Remove any recently installed compression filters and try again.
+#define ERR_INVALID_OFFSET -1074395971 // The offset you specified must be size 2.
+#define ERR_INIT -1074395960 // Initialization error.
+#define ERR_CREATE_WINDOW -1074395959 // Unable to create window.
+#define ERR_WINDOW_ID -1074395958 // Invalid window ID.
+#define ERR_ARRAY_SIZE_MISMATCH -1074395957 // The array sizes are not compatible.
+#define ERR_INVALID_QUALITY -1074395956 // The quality you provided is invalid. Valid quality values range from -1 to 1000.
+#define ERR_INVALID_MAX_WAVELET_TRANSFORM_LEVEL -1074395955 // Invalid maximum wavelet transform level. Valid values range from 0 to 255.
+#define ERR_INVALID_QUANTIZATION_STEP_SIZE -1074395954 // The quantization step size must be greater than or equal to 0.
+#define ERR_INVALID_WAVELET_TRANSFORM_MODE -1074395953 // Invalid wavelet transform mode.
+#define ERR_ROI_NOT_POINT -1074395952 // The ROI must only have a single Point contour.
+#define ERR_ROI_NOT_POINTS -1074395951 // The ROI must only have Point contours.
+#define ERR_ROI_NOT_LINE -1074395950 // The ROI must only have a single Line contour.
+#define ERR_ROI_NOT_ANNULUS -1074395949 // The ROI must only have a single Annulus contour.
+#define ERR_INVALID_MEASURE_PARTICLES_CALIBRATION_MODE -1074395948 // Invalid measure particles calibration mode.
+#define ERR_INVALID_PARTICLE_CLASSIFIER_THRESHOLD_TYPE -1074395947 // Invalid particle classifier threshold type.
+#define ERR_INVALID_DISTANCE -1074395946 // Invalid Color Segmentation Distance
+#define ERR_INVALID_PARTICLE_AREA -1074395945 // Invalid Color Segmenation Particle Area
+#define ERR_CLASS_NAME_NOT_FOUND -1074395944 // Required Class name is not found in trained labels/Class names
+#define ERR_NUMBER_LABEL_LIMIT_EXCEEDED -1074395943 // Number of Labels exceeded limit of label Image type
+#define ERR_INVALID_DISTANCE_LEVEL -1074395942 // Invalid Color Segmentation distance level
+#define ERR_INVALID_SVM_TYPE -1074395941 // Invalid SVM model type
+#define ERR_INVALID_SVM_KERNEL -1074395940 // Invalid SVM kernel type
+#define ERR_NO_SUPPORT_VECTOR_FOUND -1074395939 // No Support Vector is found at SVM training
+#define ERR_COST_LABEL_NOT_FOUND -1074395938 // Label name is not found in added samples
+#define ERR_EXCEEDED_SVM_MAX_ITERATION -1074395937 // SVM training exceeded maximim Iteration limit
+#define ERR_INVALID_SVM_PARAMETER -1074395936 // Invalid SVM Parameter
+#define ERR_INVALID_IDENTIFICATION_SCORE -1074395935 // Invalid Identification score. Must be between 0-1000.
+#define ERR_INVALID_TEXTURE_FEATURE -1074395934 // Requested for invalid texture feature
+#define ERR_INVALID_COOCCURRENCE_LEVEL -1074395933 // The coOccurrence Level must lie between 1 and the maximum pixel value of an image (255 for U8 image)
+#define ERR_INVALID_WAVELET_SUBBAND -1074395932 // Request for invalid wavelet subBand
+#define ERR_INVALID_FINAL_STEP_SIZE -1074395931 // The final step size must be lesser than the initial step size
+#define ERR_INVALID_ENERGY -1074395930 // Minimum Energy should lie between 0 and 100
+#define ERR_INVALID_TEXTURE_LABEL -1074395929 // The classification label must be texture or defect for texture defect classifier
+#define ERR_INVALID_WAVELET_TYPE -1074395928 // The wavelet type is invalid
+#define ERR_SAME_WAVELET_BANDS_SELECTED -1074395927 // Same Wavelet band is selected multiple times
+#define ERR_IMAGE_SIZE_MISMATCH -1074395926 // The two input image sizes are different
+#define ERR_NUMBER_CLASS -1074395920 // Invalid number of classes.
+#define ERR_INVALID_LUCAS_KANADE_WINDOW_SIZE -1074395888 // Both dimensions of the window size should be odd, greater than 2 and less than 16.
+#define ERR_INVALID_MATRIX_TYPE -1074395887 // The type of matrix supplied to the function is not supported.
+#define ERR_INVALID_OPTICAL_FLOW_TERMINATION_CRITERIA_TYPE -1074395886 // An invalid termination criteria was specified for the optical flow computation.
+#define ERR_LKP_NULL_PYRAMID -1074395885 // The pyramid levels where not properly allocated.
+#define ERR_INVALID_PYRAMID_LEVEL -1074395884 // The pyramid level specified cannot be negative
+#define ERR_INVALID_LKP_KERNEL -1074395883 // The kernel must be symmetric with non-zero coefficients and of odd size
+#define ERR_INVALID_HORN_SCHUNCK_LAMBDA -1074395882 // Invalid smoothing parameter in Horn Schunck operation.
+#define ERR_INVALID_HORN_SCHUNCK_TYPE -1074395881 // Invalid stopping criteria type for Horn Schunck optical flow.
+#define ERR_PARTICLE -1074395880 // Invalid particle.
+#define ERR_BAD_MEASURE -1074395879 // Invalid measure number.
+#define ERR_PROP_NODE_WRITE_NOT_SUPPORTED -1074395878 // The Image Display control does not support writing this property node.
+#define ERR_COLORMODE_REQUIRES_CHANGECOLORSPACE2 -1074395877 // The specified color mode requires the use of imaqChangeColorSpace2.
+#define ERR_UNSUPPORTED_COLOR_MODE -1074395876 // This function does not currently support the color mode you specified.
+#define ERR_BARCODE_PHARMACODE -1074395875 // The barcode is not a valid Pharmacode symbol
+#define ERR_BAD_INDEX -1074395840 // Invalid handle table index.
+#define ERR_INVALID_COMPRESSION_RATIO -1074395837 // The compression ratio must be greater than or equal to 1.
+#define ERR_TOO_MANY_CONTOURS -1074395801 // The ROI contains too many contours.
+#define ERR_PROTECTION -1074395800 // Protection error.
+#define ERR_INTERNAL -1074395799 // Internal error.
+#define ERR_INVALID_CUSTOM_SAMPLE -1074395798 // The size of the feature vector in the custom sample must match the size of those you have already added.
+#define ERR_INVALID_CLASSIFIER_SESSION -1074395797 // Not a valid classifier session.
+#define ERR_INVALID_KNN_METHOD -1074395796 // You requested an invalid Nearest Neighbor classifier method.
+#define ERR_K_TOO_LOW -1074395795 // The k parameter must be greater than two.
+#define ERR_K_TOO_HIGH -1074395794 // The k parameter must be <= the number of samples in each class.
+#define ERR_INVALID_OPERATION_ON_COMPACT_SESSION_ATTEMPTED -1074395793 // This classifier session is compact. Only the Classify and Dispose functions may be called on a compact classifier session.
+#define ERR_CLASSIFIER_SESSION_NOT_TRAINED -1074395792 // This classifier session is not trained. You may only call this function on a trained classifier session.
+#define ERR_CLASSIFIER_INVALID_SESSION_TYPE -1074395791 // This classifier function cannot be called on this type of classifier session.
+#define ERR_INVALID_DISTANCE_METRIC -1074395790 // You requested an invalid distance metric.
+#define ERR_OPENING_NEWER_CLASSIFIER_SESSION -1074395789 // The classifier session you tried to open was created with a newer version of NI Vision. Upgrade to the latest version of NI Vision to read this file.
+#define ERR_NO_SAMPLES -1074395788 // This operation cannot be performed because you have not added any samples.
+#define ERR_INVALID_CLASSIFIER_TYPE -1074395787 // You requested an invalid classifier type.
+#define ERR_INVALID_PARTICLE_OPTIONS -1074395786 // The sum of Scale Dependence and Symmetry Dependence must be less than 1000.
+#define ERR_NO_PARTICLE -1074395785 // The image yielded no particles.
+#define ERR_INVALID_LIMITS -1074395784 // The limits you supplied are not valid.
+#define ERR_BAD_SAMPLE_INDEX -1074395783 // The Sample Index fell outside the range of Samples.
+#define ERR_DESCRIPTION_TOO_LONG -1074395782 // The description must be <= 255 characters.
+#define ERR_CLASSIFIER_INVALID_ENGINE_TYPE -1074395781 // The engine for this classifier session does not support this operation.
+#define ERR_INVALID_PARTICLE_TYPE -1074395780 // You requested an invalid particle type.
+#define ERR_CANNOT_COMPACT_UNTRAINED -1074395779 // You may only save a session in compact form if it is trained.
+#define ERR_INVALID_KERNEL_SIZE -1074395778 // The Kernel size must be smaller than the image size.
+#define ERR_INCOMPATIBLE_CLASSIFIER_TYPES -1074395777 // The session you read from file must be the same type as the session you passed in.
+#define ERR_INVALID_USE_OF_COMPACT_SESSION_FILE -1074395776 // You can not use a compact classification file with read options other than Read All.
+#define ERR_ROI_HAS_OPEN_CONTOURS -1074395775 // The ROI you passed in may only contain closed contours.
+#define ERR_NO_LABEL -1074395774 // You must pass in a label.
+#define ERR_NO_DEST_IMAGE -1074395773 // You must provide a destination image.
+#define ERR_INVALID_REGISTRATION_METHOD -1074395772 // You provided an invalid registration method.
+#define ERR_OPENING_NEWER_INSPECTION_TEMPLATE -1074395771 // The golden template you tried to open was created with a newer version of NI Vision. Upgrade to the latest version of NI Vision to read this file.
+#define ERR_INVALID_INSPECTION_TEMPLATE -1074395770 // Invalid golden template.
+#define ERR_INVALID_EDGE_THICKNESS -1074395769 // Edge Thickness to Ignore must be greater than zero.
+#define ERR_INVALID_SCALE -1074395768 // Scale must be greater than zero.
+#define ERR_INVALID_ALIGNMENT -1074395767 // The supplied scale is invalid for your template.
+#define ERR_DEPRECATED_FUNCTION -1074395766 // This backwards-compatibility function can not be used with this session. Use newer, supported functions instead.
+#define ERR_INVALID_NORMALIZATION_METHOD -1074395763 // You must provide a valid normalization method.
+#define ERR_INVALID_NIBLACK_DEVIATION_FACTOR -1074395762 // The deviation factor for Niblack local threshold must be between 0 and 1.
+#define ERR_BOARD_NOT_FOUND -1074395760 // Board not found.
+#define ERR_BOARD_NOT_OPEN -1074395758 // Board not opened.
+#define ERR_DLL_NOT_FOUND -1074395757 // DLL not found.
+#define ERR_DLL_FUNCTION_NOT_FOUND -1074395756 // DLL function not found.
+#define ERR_TRIG_TIMEOUT -1074395754 // Trigger timeout.
+#define ERR_CONTOUR_INVALID_REFINEMENTS -1074395746 // Invalid number specified for maximum contour refinements.
+#define ERR_TOO_MANY_CURVES -1074395745 // Too many curves extracted from image. Raise the edge threshold or reduce the ROI.
+#define ERR_CONTOUR_INVALID_KERNEL_FOR_SMOOTHING -1074395744 // Invalid kernel for contour smoothing. Zero indicates no smoothing, otherwise value must be odd.
+#define ERR_CONTOUR_LINE_INVALID -1074395743 // The contour line fit is invalid. Line segment start and stop must differ.
+#define ERR_CONTOUR_TEMPLATE_IMAGE_INVALID -1074395742 // The template image must be trained with IMAQ Learn Contour Pattern or be the same size as the target image.
+#define ERR_CONTOUR_GPM_FAIL -1074395741 // Matching failed to align the template and target contours.
+#define ERR_CONTOUR_OPENING_NEWER_VERSION -1074395740 // The contour you tried to open was created with a newer version of NI Vision. Upgrade to the latest version of NI Vision to read this file.
+#define ERR_CONTOUR_CONNECT_DUPLICATE -1074395739 // Only one range is allowed per curve connection constraint type.
+#define ERR_CONTOUR_CONNECT_TYPE -1074395738 // Invalid contour connection constraint type.
+#define ERR_CONTOUR_MATCH_STR_NOT_APPLICABLE -1074395737 // In order to use contour matching, you must provide a template image that has been trained with IMAQ Learn Contour Pattern
+#define ERR_CONTOUR_CURVATURE_KERNEL -1074395736 // Invalid kernel width for curvature calculation. Must be an odd value greater than 1.
+#define ERR_CONTOUR_EXTRACT_SELECTION -1074395735 // Invalid Contour Selection method for contour extraction.
+#define ERR_CONTOUR_EXTRACT_DIRECTION -1074395734 // Invalid Search Direction for contour extraction.
+#define ERR_CONTOUR_EXTRACT_ROI -1074395733 // Invalid ROI for contour extraction. The ROI must contain an annulus, rectangle or rotated rectangle.
+#define ERR_CONTOUR_NO_CURVES -1074395732 // No curves were found in the image.
+#define ERR_CONTOUR_COMPARE_KERNEL -1074395731 // Invalid Smoothing Kernel width for contour comparison. Must be zero or an odd positive integer.
+#define ERR_CONTOUR_COMPARE_SINGLE_IMAGE -1074395730 // If no template image is provided, the target image must contain both a contour with extracted points and a fitted equation.
+#define ERR_CONTOUR_INVALID -1074395729 // Invalid contour image.
+#define ERR_INVALID_2D_BARCODE_SEARCH_MODE -1074395728 // NI Vision does not support the search mode you provided.
+#define ERR_UNSUPPORTED_2D_BARCODE_SEARCH_MODE -1074395727 // NI Vision does not support the search mode you provided for the type of 2D barcode for which you are searching.
+#define ERR_MATCHFACTOR_OBSOLETE -1074395726 // matchFactor has been obsoleted. Instead, set the initialMatchListLength and matchListReductionFactor in the MatchPatternAdvancedOptions structure.
+#define ERR_DATA_VERSION -1074395725 // The data was stored with a newer version of NI Vision. Upgrade to the latest version of NI Vision to read this data.
+#define ERR_CUSTOMDATA_INVALID_SIZE -1074395724 // The size you specified is out of the valid range.
+#define ERR_CUSTOMDATA_KEY_NOT_FOUND -1074395723 // The key you specified cannot be found in the image.
+#define ERR_CLASSIFIER_CLASSIFY_IMAGE_WITH_CUSTOM_SESSION -1074395722 // Custom classifier sessions only classify feature vectors. They do not support classifying images.
+#define ERR_INVALID_BIT_DEPTH -1074395721 // NI Vision does not support the bit depth you supplied for the image you supplied.
+#define ERR_BAD_ROI -1074395720 // Invalid ROI.
+#define ERR_BAD_ROI_BOX -1074395719 // Invalid ROI global rectangle.
+#define ERR_LAB_VERSION -1074395718 // The version of LabVIEW or BridgeVIEW you are running does not support this operation.
+#define ERR_INVALID_RANGE -1074395717 // The range you supplied is invalid.
+#define ERR_INVALID_SCALING_METHOD -1074395716 // NI Vision does not support the scaling method you provided.
+#define ERR_INVALID_CALIBRATION_UNIT -1074395715 // NI Vision does not support the calibration unit you supplied.
+#define ERR_INVALID_AXIS_ORIENTATION -1074395714 // NI Vision does not support the axis orientation you supplied.
+#define ERR_VALUE_NOT_IN_ENUM -1074395713 // Value not in enumeration.
+#define ERR_WRONG_REGION_TYPE -1074395712 // You selected a region that is not of the right type.
+#define ERR_NOT_ENOUGH_REGIONS -1074395711 // You specified a viewer that does not contain enough regions.
+#define ERR_TOO_MANY_PARTICLES -1074395710 // The image has too many particles for this process.
+#define ERR_AVI_UNOPENED_SESSION -1074395709 // The AVI session has not been opened.
+#define ERR_AVI_READ_SESSION_REQUIRED -1074395708 // The AVI session is a write session, but this operation requires a read session.
+#define ERR_AVI_WRITE_SESSION_REQUIRED -1074395707 // The AVI session is a read session, but this operation requires a write session.
+#define ERR_AVI_SESSION_ALREADY_OPEN -1074395706 // This AVI session is already open. You must close it before calling the Create or Open functions.
+#define ERR_DATA_CORRUPTED -1074395705 // The data is corrupted and cannot be read.
+#define ERR_INVALID_COMPRESSION_TYPE -1074395704 // Invalid compression type.
+#define ERR_INVALID_TYPE_OF_FLATTEN -1074395703 // Invalid type of flatten.
+#define ERR_INVALID_LENGTH -1074395702 // The length of the edge detection line must be greater than zero.
+#define ERR_INVALID_MATRIX_SIZE_RANGE -1074395701 // The maximum Data Matrix barcode size must be equal to or greater than the minimum Data Matrix barcode size.
+#define ERR_REQUIRES_WIN2000_OR_NEWER -1074395700 // The function requires the operating system to be Microsoft Windows 2000 or newer.
+#define ERR_INVALID_CALIBRATION_METHOD -1074395662 // Invalid calibration method requested
+#define ERR_INVALID_OPERATION_ON_COMPACT_CALIBRATION_ATTEMPTED -1074395661 // This calibration is compact. Re-Learning calibration and retrieving thumbnails are not possible with this calibration
+#define ERR_INVALID_POLYNOMIAL_MODEL_K_COUNT -1074395660 // Invalid number of K values
+#define ERR_INVALID_DISTORTION_MODEL -1074395659 // Invalid distortion model type
+#define ERR_CAMERA_MODEL_NOT_AVAILABLE -1074395658 // Camera Model is not learned
+#define ERR_INVALID_THUMBNAIL_INDEX -1074395657 // Supplied thumbnail index is invalid
+#define ERR_SMOOTH_CONTOURS_MUST_BE_SAME -1074395656 // You must specify the same value for the smooth contours advanced match option for all templates you want to match.
+#define ERR_ENABLE_CALIBRATION_SUPPORT_MUST_BE_SAME -1074395655 // You must specify the same value for the enable calibration support advanced match option for all templates you want to match.
+#define ERR_GRADING_INFORMATION_NOT_FOUND -1074395654 // The source image does not contain grading information. You must prepare the source image for grading when reading the Data Matrix, and you cannot change the contents of the source image between reading and grading the Data Matrix.
+#define ERR_OPENING_NEWER_MULTIPLE_GEOMETRIC_TEMPLATE -1074395653 // The multiple geometric matching template you tried to open was created with a newer version of NI Vision. Upgrade to the latest version of NI Vision to read this file.
+#define ERR_OPENING_NEWER_GEOMETRIC_MATCHING_TEMPLATE -1074395652 // The geometric matching template you tried to open was created with a newer version of NI Vision. Upgrade to the latest version of NI Vision to read this file.
+#define ERR_EDGE_FILTER_SIZE_MUST_BE_SAME -1074395651 // You must specify the same edge filter size for all the templates you want to match.
+#define ERR_CURVE_EXTRACTION_MODE_MUST_BE_SAME -1074395650 // You must specify the same curve extraction mode for all the templates you want to match.
+#define ERR_INVALID_GEOMETRIC_FEATURE_TYPE -1074395649 // The geometric feature type specified is invalid.
+#define ERR_TEMPLATE_NOT_LEARNED -1074395648 // You supplied a template that was not learned.
+#define ERR_INVALID_MULTIPLE_GEOMETRIC_TEMPLATE -1074395647 // Invalid multiple geometric template.
+#define ERR_NO_TEMPLATE_TO_LEARN -1074395646 // Need at least one template to learn.
+#define ERR_INVALID_NUMBER_OF_LABELS -1074395645 // You supplied an invalid number of labels.
+#define ERR_LABEL_TOO_LONG -1074395644 // Labels must be <= 255 characters.
+#define ERR_INVALID_NUMBER_OF_MATCH_OPTIONS -1074395643 // You supplied an invalid number of match options.
+#define ERR_LABEL_NOT_FOUND -1074395642 // Cannot find a label that matches the one you specified.
+#define ERR_DUPLICATE_LABEL -1074395641 // Duplicate labels are not allowed.
+#define ERR_TOO_MANY_ZONES -1074395640 // The number of zones found exceeded the capacity of the algorithm.
+#define ERR_INVALID_HATCH_STYLE -1074395639 // The hatch style for the window background is invalid.
+#define ERR_INVALID_FILL_STYLE -1074395638 // The fill style for the window background is invalid.
+#define ERR_HARDWARE_DOESNT_SUPPORT_NONTEARING -1074395637 // Your hardware is not supported by DirectX and cannot be put into NonTearing mode.
+#define ERR_DIRECTX_NOT_FOUND -1074395636 // DirectX is required for this feature. Please install the latest version..
+#define ERR_INVALID_SHAPE_DESCRIPTOR -1074395635 // The passed shape descriptor is invalid.
+#define ERR_INVALID_MAX_MATCH_OVERLAP -1074395634 // Invalid max match overlap. Values must be between -1 and 100.
+#define ERR_INVALID_MIN_MATCH_SEPARATION_SCALE -1074395633 // Invalid minimum match separation scale. Values must be greater than or equal to -1.
+#define ERR_INVALID_MIN_MATCH_SEPARATION_ANGLE -1074395632 // Invalid minimum match separation angle. Values must be between -1 and 360.
+#define ERR_INVALID_MIN_MATCH_SEPARATION_DISTANCE -1074395631 // Invalid minimum match separation distance. Values must be greater than or equal to -1.
+#define ERR_INVALID_MAXIMUM_FEATURES_LEARNED -1074395630 // Invalid maximum number of features learn. Values must be integers greater than zero.
+#define ERR_INVALID_MAXIMUM_PIXEL_DISTANCE_FROM_LINE -1074395629 // Invalid maximum pixel distance from line. Values must be positive real numbers.
+#define ERR_INVALID_GEOMETRIC_MATCHING_TEMPLATE -1074395628 // Invalid geometric matching template image.
+#define ERR_NOT_ENOUGH_TEMPLATE_FEATURES_1 -1074395627 // The template does not contain enough features for geometric matching.
+#define ERR_NOT_ENOUGH_TEMPLATE_FEATURES -1074395626 // The template does not contain enough features for geometric matching.
+#define ERR_INVALID_MATCH_CONSTRAINT_TYPE -1074395625 // You specified an invalid value for the match constraint value of the range settings.
+#define ERR_INVALID_OCCLUSION_RANGE -1074395624 // Invalid occlusion range. Valid values for the bounds range from 0 to 100 and the upper bound must be greater than or equal to the lower bound.
+#define ERR_INVALID_SCALE_RANGE -1074395623 // Invalid scale range. Values for the lower bound must be a positive real numbers and the upper bound must be greater than or equal to the lower bound.
+#define ERR_INVALID_MATCH_GEOMETRIC_PATTERN_SETUP_DATA -1074395622 // Invalid match geometric pattern setup data.
+#define ERR_INVALID_LEARN_GEOMETRIC_PATTERN_SETUP_DATA -1074395621 // Invalid learn geometric pattern setup data.
+#define ERR_INVALID_CURVE_EXTRACTION_MODE -1074395620 // Invalid curve extraction mode.
+#define ERR_TOO_MANY_OCCLUSION_RANGES -1074395619 // You can specify only one occlusion range.
+#define ERR_TOO_MANY_SCALE_RANGES -1074395618 // You can specify only one scale range.
+#define ERR_INVALID_NUMBER_OF_FEATURES_RANGE -1074395617 // The minimum number of features must be less than or equal to the maximum number of features.
+#define ERR_INVALID_EDGE_FILTER_SIZE -1074395616 // Invalid edge filter size.
+#define ERR_INVALID_MINIMUM_FEATURE_STRENGTH -1074395615 // Invalid minimum strength for features. Values must be positive real numbers.
+#define ERR_INVALID_MINIMUM_FEATURE_ASPECT_RATIO -1074395614 // Invalid aspect ratio for rectangular features. Values must be positive real numbers in the range 0.01 to 1.0.
+#define ERR_INVALID_MINIMUM_FEATURE_LENGTH -1074395613 // Invalid minimum length for linear features. Values must be integers greater than 0.
+#define ERR_INVALID_MINIMUM_FEATURE_RADIUS -1074395612 // Invalid minimum radius for circular features. Values must be integers greater than 0.
+#define ERR_INVALID_MINIMUM_RECTANGLE_DIMENSION -1074395611 // Invalid minimum rectangle dimension. Values must be integers greater than 0.
+#define ERR_INVALID_INITIAL_MATCH_LIST_LENGTH -1074395610 // Invalid initial match list length. Values must be integers greater than 5.
+#define ERR_INVALID_SUBPIXEL_TOLERANCE -1074395609 // Invalid subpixel tolerance. Values must be positive real numbers.
+#define ERR_INVALID_SUBPIXEL_ITERATIONS -1074395608 // Invalid number of subpixel iterations. Values must be integers greater 10.
+#define ERR_INVALID_MAXIMUM_FEATURES_PER_MATCH -1074395607 // Invalid maximum number of features used per match. Values must be integers greater than or equal to zero.
+#define ERR_INVALID_MINIMUM_FEATURES_TO_MATCH -1074395606 // Invalid minimum number of features used for matching. Values must be integers greater than zero.
+#define ERR_INVALID_MAXIMUM_END_POINT_GAP -1074395605 // Invalid maximum end point gap. Valid values range from 0 to 32767.
+#define ERR_INVALID_COLUMN_STEP -1074395604 // Invalid column step. Valid range is 1 to 255.
+#define ERR_INVALID_ROW_STEP -1074395603 // Invalid row step. Valid range is 1 to 255.
+#define ERR_INVALID_MINIMUM_CURVE_LENGTH -1074395602 // Invalid minimum length. Valid values must be greater than or equal to zero.
+#define ERR_INVALID_EDGE_THRESHOLD -1074395601 // Invalid edge threshold. Valid values range from 1 to 360.
+#define ERR_INFO_NOT_FOUND -1074395600 // You must provide information about the subimage within the browser.
+#define ERR_NIOCR_INVALID_ACCEPTANCE_LEVEL -1074395598 // The acceptance level is outside the valid range of 0 to 1000.
+#define ERR_NIOCR_NOT_A_VALID_SESSION -1074395597 // Not a valid OCR session.
+#define ERR_NIOCR_INVALID_CHARACTER_SIZE -1074395596 // Invalid character size. Character size must be >= 1.
+#define ERR_NIOCR_INVALID_THRESHOLD_MODE -1074395595 // Invalid threshold mode value.
+#define ERR_NIOCR_INVALID_SUBSTITUTION_CHARACTER -1074395594 // Invalid substitution character. Valid substitution characters are ASCII values that range from 1 to 254.
+#define ERR_NIOCR_INVALID_NUMBER_OF_BLOCKS -1074395593 // Invalid number of blocks. Number of blocks must be >= 4 and <= 50.
+#define ERR_NIOCR_INVALID_READ_STRATEGY -1074395592 // Invalid read strategy.
+#define ERR_NIOCR_INVALID_CHARACTER_INDEX -1074395591 // Invalid character index.
+#define ERR_NIOCR_INVALID_NUMBER_OF_VALID_CHARACTER_POSITIONS -1074395590 // Invalid number of character positions. Valid values range from 0 to 255.
+#define ERR_NIOCR_INVALID_LOW_THRESHOLD_VALUE -1074395589 // Invalid low threshold value. Valid threshold values range from 0 to 255.
+#define ERR_NIOCR_INVALID_HIGH_THRESHOLD_VALUE -1074395588 // Invalid high threshold value. Valid threshold values range from 0 to 255.
+#define ERR_NIOCR_INVALID_THRESHOLD_RANGE -1074395587 // The low threshold must be less than the high threshold.
+#define ERR_NIOCR_INVALID_LOWER_THRESHOLD_LIMIT -1074395586 // Invalid lower threshold limit. Valid lower threshold limits range from 0 to 255.
+#define ERR_NIOCR_INVALID_UPPER_THRESHOLD_LIMIT -1074395585 // Invalid upper threshold limit. Valid upper threshold limits range from 0 to 255.
+#define ERR_NIOCR_INVALID_THRESHOLD_LIMITS -1074395584 // The lower threshold limit must be less than the upper threshold limit.
+#define ERR_NIOCR_INVALID_MIN_CHAR_SPACING -1074395583 // Invalid minimum character spacing value. Character spacing must be >= 1 pixel.
+#define ERR_NIOCR_INVALID_MAX_HORIZ_ELEMENT_SPACING -1074395582 // Invalid maximum horizontal element spacing value. Maximum horizontal element spacing must be >= 0.
+#define ERR_NIOCR_INVALID_MAX_VERT_ELEMENT_SPACING -1074395581 // Invalid maximum vertical element spacing value. Maximum vertical element spacing must be >= 0.
+#define ERR_NIOCR_INVALID_MIN_BOUNDING_RECT_WIDTH -1074395580 // Invalid minimum bounding rectangle width. Minimum bounding rectangle width must be >= 1.
+#define ERR_NIOCR_INVALID_ASPECT_RATIO -1074395579 // Invalid aspect ratio value. The aspect ratio must be zero or >= 100.
+#define ERR_NIOCR_INVALID_CHARACTER_SET_FILE -1074395578 // Invalid or corrupt character set file.
+#define ERR_NIOCR_CHARACTER_VALUE_CANNOT_BE_EMPTYSTRING -1074395577 // The character value must not be an empty string.
+#define ERR_NIOCR_CHARACTER_VALUE_TOO_LONG -1074395576 // Character values must be <=255 characters.
+#define ERR_NIOCR_INVALID_NUMBER_OF_EROSIONS -1074395575 // Invalid number of erosions. The number of erosions must be >= 0.
+#define ERR_NIOCR_CHARACTER_SET_DESCRIPTION_TOO_LONG -1074395574 // The character set description must be <=255 characters.
+#define ERR_NIOCR_INVALID_CHARACTER_SET_FILE_VERSION -1074395573 // The character set file was created by a newer version of NI Vision. Upgrade to the latest version of NI Vision to read the character set file.
+#define ERR_NIOCR_INTEGER_VALUE_FOR_STRING_ATTRIBUTE -1074395572 // You must specify characters for a string. A string cannot contain integers.
+#define ERR_NIOCR_GET_ONLY_ATTRIBUTE -1074395571 // This attribute is read-only.
+#define ERR_NIOCR_INTEGER_VALUE_FOR_BOOLEAN_ATTRIBUTE -1074395570 // This attribute requires a Boolean value.
+#define ERR_NIOCR_INVALID_ATTRIBUTE -1074395569 // Invalid attribute.
+#define ERR_NIOCR_STRING_VALUE_FOR_INTEGER_ATTRIBUTE -1074395568 // This attribute requires integer values.
+#define ERR_NIOCR_STRING_VALUE_FOR_BOOLEAN_ATTRIBUTE -1074395567 // String values are invalid for this attribute. Enter a boolean value.
+#define ERR_NIOCR_BOOLEAN_VALUE_FOR_INTEGER_ATTRIBUTE -1074395566 // Boolean values are not valid for this attribute. Enter an integer value.
+#define ERR_NIOCR_MUST_BE_SINGLE_CHARACTER -1074395565 // Requires a single-character string.
+#define ERR_NIOCR_INVALID_PREDEFINED_CHARACTER -1074395564 // Invalid predefined character value.
+#define ERR_NIOCR_UNLICENSED -1074395563 // This copy of NI OCR is unlicensed.
+#define ERR_NIOCR_BOOLEAN_VALUE_FOR_STRING_ATTRIBUTE -1074395562 // String values are not valid for this attribute. Enter a Boolean value.
+#define ERR_NIOCR_INVALID_NUMBER_OF_CHARACTERS -1074395561 // The number of characters in the character value must match the number of objects in the image.
+#define ERR_NIOCR_INVALID_OBJECT_INDEX -1074395560 // Invalid object index.
+#define ERR_NIOCR_INVALID_READ_OPTION -1074395559 // Invalid read option.
+#define ERR_NIOCR_INVALID_CHARACTER_SIZE_RANGE -1074395558 // The minimum character size must be less than the maximum character size.
+#define ERR_NIOCR_INVALID_BOUNDING_RECT_WIDTH_RANGE -1074395557 // The minimum character bounding rectangle width must be less than the maximum character bounding rectangle width.
+#define ERR_NIOCR_INVALID_BOUNDING_RECT_HEIGHT_RANGE -1074395556 // The minimum character bounding rectangle height must be less than the maximum character bounding rectangle height.
+#define ERR_NIOCR_INVALID_SPACING_RANGE -1074395555 // The maximum horizontal element spacing value must not exceed the minimum character spacing value.
+#define ERR_NIOCR_INVALID_READ_RESOLUTION -1074395554 // Invalid read resolution.
+#define ERR_NIOCR_INVALID_MIN_BOUNDING_RECT_HEIGHT -1074395553 // Invalid minimum bounding rectangle height. The minimum bounding rectangle height must be >= 1.
+#define ERR_NIOCR_NOT_A_VALID_CHARACTER_SET -1074395552 // Not a valid character set.
+#define ERR_NIOCR_RENAME_REFCHAR -1074395551 // A trained OCR character cannot be renamed while it is a reference character.
+#define ERR_NIOCR_INVALID_CHARACTER_VALUE -1074395550 // A character cannot have an ASCII value of 255.
+#define ERR_NIOCR_INVALID_NUMBER_OF_OBJECTS_TO_VERIFY -1074395549 // The number of objects found does not match the number of expected characters or patterns to verify.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_PREFILTER_CAP -1074395421 // The specified value for the filter cap for block matching is invalid.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_PREFILTER_SIZE -1074395420 // The specified prefilter size for block matching is invalid.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_PREFILTER_TYPE -1074395419 // The specified prefilter type for block matching is invalid.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_NUMDISPARITIES -1074395418 // The specifed value for number of disparities is invalid.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_WINDOW_SIZE -1074395417 // The specified window size for block matching is invalid.
+#define ERR_3DVISION_INVALID_SESSION_TYPE -1074395416 // This 3D vision function cannot be called on this type of 3d vision session.
+#define ERR_TOO_MANY_3DVISION_SESSIONS -1074395415 // There are too many 3D vision sessions open. You must close a session before you can open another one.
+#define ERR_OPENING_NEWER_3DVISION_SESSION -1074395414 // The 3D vision session you tried to open was created with a newer version of NI Vision. Upgrade to the latest version of NI Vision to read this file.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_FILTERTYPE -1074395413 // You have specified an invalid filter type for block matching.
+#define ERR_INVALID_STEREO_CAMERA_POSITION -1074395412 // You have requested results at an invalid camera position in the stereo setup.
+#define ERR_INVALID_3DVISION_SESSION -1074395411 // Not a valid 3D Vision session.
+#define ERR_INVALID_ICONS_PER_LINE -1074395410 // NI Vision does not support less than one icon per line.
+#define ERR_INVALID_SUBPIXEL_DIVISIONS -1074395409 // Invalid subpixel divisions.
+#define ERR_INVALID_DETECTION_MODE -1074395408 // Invalid detection mode.
+#define ERR_INVALID_CONTRAST -1074395407 // Invalid contrast value. Valid contrast values range from 0 to 255.
+#define ERR_COORDSYS_NOT_FOUND -1074395406 // The coordinate system could not be found on this image.
+#define ERR_INVALID_TEXTORIENTATION -1074395405 // NI Vision does not support the text orientation value you supplied.
+#define ERR_INVALID_INTERPOLATIONMETHOD_FOR_UNWRAP -1074395404 // UnwrapImage does not support the interpolation method value you supplied. Valid interpolation methods are zero order and bilinear.
+#define ERR_EXTRAINFO_VERSION -1074395403 // The image was created in a newer version of NI Vision. Upgrade to the latest version of NI Vision to use this image.
+#define ERR_INVALID_MAXPOINTS -1074395402 // The function does not support the maximum number of points that you specified.
+#define ERR_INVALID_MATCHFACTOR -1074395401 // The function does not support the matchFactor that you specified.
+#define ERR_MULTICORE_OPERATION -1074395400 // The operation you have given Multicore Options is invalid. Please see the available enumeration values for Multicore Operation.
+#define ERR_MULTICORE_INVALID_ARGUMENT -1074395399 // You have given Multicore Options an invalid argument.
+#define ERR_COMPLEX_IMAGE_REQUIRED -1074395397 // A complex image is required.
+#define ERR_COLOR_IMAGE_REQUIRED -1074395395 // The input image must be a color image.
+#define ERR_COLOR_SPECTRUM_MASK -1074395394 // The color mask removes too much color information.
+#define ERR_COLOR_TEMPLATE_IMAGE_TOO_SMALL -1074395393 // The color template image is too small.
+#define ERR_COLOR_TEMPLATE_IMAGE_TOO_LARGE -1074395392 // The color template image is too large.
+#define ERR_COLOR_TEMPLATE_IMAGE_HUE_CONTRAST_TOO_LOW -1074395391 // The contrast in the hue plane of the image is too low for learning shape features.
+#define ERR_COLOR_TEMPLATE_IMAGE_LUMINANCE_CONTRAST_TOO_LOW -1074395390 // The contrast in the luminance plane of the image is too low to learn shape features.
+#define ERR_COLOR_LEARN_SETUP_DATA -1074395389 // Invalid color learn setup data.
+#define ERR_COLOR_LEARN_SETUP_DATA_SHAPE -1074395388 // Invalid color learn setup data.
+#define ERR_COLOR_MATCH_SETUP_DATA -1074395387 // Invalid color match setup data.
+#define ERR_COLOR_MATCH_SETUP_DATA_SHAPE -1074395386 // Invalid color match setup data.
+#define ERR_COLOR_ROTATION_REQUIRES_SHAPE_FEATURE -1074395385 // Rotation-invariant color pattern matching requires a feature mode including shape.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR -1074395384 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_1 -1074395383 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_2 -1074395382 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_3 -1074395381 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_4 -1074395380 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_5 -1074395379 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_6 -1074395378 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT -1074395377 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSHIFT -1074395376 // The color template image does not contain data required for shift-invariant color matching.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT_1 -1074395375 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT_2 -1074395374 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION -1074395373 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_NOROTATION -1074395372 // The color template image does not contain data required for rotation-invariant color matching.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_1 -1074395371 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_2 -1074395370 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_3 -1074395369 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_4 -1074395368 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_5 -1074395367 // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSHAPE -1074395366 // The color template image does not contain data required for color matching in shape feature mode.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSPECTRUM -1074395365 // The color template image does not contain data required for color matching in color feature mode.
+#define ERR_IGNORE_COLOR_SPECTRUM_SET -1074395364 // The ignore color spectra array is invalid.
+#define ERR_INVALID_SUBSAMPLING_RATIO -1074395363 // Invalid subsampling ratio.
+#define ERR_INVALID_WIDTH -1074395362 // Invalid pixel width.
+#define ERR_INVALID_STEEPNESS -1074395361 // Invalid steepness.
+#define ERR_COMPLEX_PLANE -1074395360 // Invalid complex plane.
+#define ERR_INVALID_COLOR_IGNORE_MODE -1074395357 // Invalid color ignore mode.
+#define ERR_INVALID_MIN_MATCH_SCORE -1074395356 // Invalid minimum match score. Acceptable values range from 0 to 1000.
+#define ERR_INVALID_NUM_MATCHES_REQUESTED -1074395355 // Invalid number of matches requested. You must request a minimum of one match.
+#define ERR_INVALID_COLOR_WEIGHT -1074395354 // Invalid color weight. Acceptable values range from 0 to 1000.
+#define ERR_INVALID_SEARCH_STRATEGY -1074395353 // Invalid search strategy.
+#define ERR_INVALID_FEATURE_MODE -1074395352 // Invalid feature mode.
+#define ERR_INVALID_RECT -1074395351 // NI Vision does not support rectangles with negative widths or negative heights.
+#define ERR_INVALID_VISION_INFO -1074395350 // NI Vision does not support the vision information type you supplied.
+#define ERR_INVALID_SKELETONMETHOD -1074395349 // NI Vision does not support the SkeletonMethod value you supplied.
+#define ERR_INVALID_3DPLANE -1074395348 // NI Vision does not support the 3DPlane value you supplied.
+#define ERR_INVALID_3DDIRECTION -1074395347 // NI Vision does not support the 3DDirection value you supplied.
+#define ERR_INVALID_INTERPOLATIONMETHOD_FOR_ROTATE -1074395346 // imaqRotate does not support the InterpolationMethod value you supplied.
+#define ERR_INVALID_FLIPAXIS -1074395345 // NI Vision does not support the axis of symmetry you supplied.
+#define ERR_FILE_FILENAME_NULL -1074395343 // You must pass a valid file name. Do not pass in NULL.
+#define ERR_INVALID_SIZETYPE -1074395340 // NI Vision does not support the SizeType value you supplied.
+#define ERR_UNKNOWN_ALGORITHM -1074395336 // You specified the dispatch status of an unknown algorithm.
+#define ERR_DISPATCH_STATUS_CONFLICT -1074395335 // You are attempting to set the same algorithm to dispatch and to not dispatch. Remove one of the conflicting settings.
+#define ERR_INVALID_CONVERSIONSTYLE -1074395334 // NI Vision does not support the Conversion Method value you supplied.
+#define ERR_INVALID_VERTICAL_TEXT_ALIGNMENT -1074395333 // NI Vision does not support the VerticalTextAlignment value you supplied.
+#define ERR_INVALID_COMPAREFUNCTION -1074395332 // NI Vision does not support the CompareFunction value you supplied.
+#define ERR_INVALID_BORDERMETHOD -1074395331 // NI Vision does not support the BorderMethod value you supplied.
+#define ERR_INVALID_BORDER_SIZE -1074395330 // Invalid border size. Acceptable values range from 0 to 50.
+#define ERR_INVALID_OUTLINEMETHOD -1074395329 // NI Vision does not support the OutlineMethod value you supplied.
+#define ERR_INVALID_INTERPOLATIONMETHOD -1074395328 // NI Vision does not support the InterpolationMethod value you supplied.
+#define ERR_INVALID_SCALINGMODE -1074395327 // NI Vision does not support the ScalingMode value you supplied.
+#define ERR_INVALID_DRAWMODE_FOR_LINE -1074395326 // imaqDrawLineOnImage does not support the DrawMode value you supplied.
+#define ERR_INVALID_DRAWMODE -1074395325 // NI Vision does not support the DrawMode value you supplied.
+#define ERR_INVALID_SHAPEMODE -1074395324 // NI Vision does not support the ShapeMode value you supplied.
+#define ERR_INVALID_FONTCOLOR -1074395323 // NI Vision does not support the FontColor value you supplied.
+#define ERR_INVALID_TEXTALIGNMENT -1074395322 // NI Vision does not support the TextAlignment value you supplied.
+#define ERR_INVALID_MORPHOLOGYMETHOD -1074395321 // NI Vision does not support the MorphologyMethod value you supplied.
+#define ERR_TEMPLATE_EMPTY -1074395320 // The template image is empty.
+#define ERR_INVALID_SUBPIX_TYPE -1074395319 // NI Vision does not support the interpolation type you supplied.
+#define ERR_INSF_POINTS -1074395318 // You supplied an insufficient number of points to perform this operation.
+#define ERR_UNDEF_POINT -1074395317 // You specified a point that lies outside the image.
+#define ERR_INVALID_KERNEL_CODE -1074395316 // Invalid kernel code.
+#define ERR_INEFFICIENT_POINTS -1074395315 // You supplied an inefficient set of points to match the minimum score.
+#define ERR_WRITE_FILE_NOT_SUPPORTED -1074395313 // Writing files is not supported on this device.
+#define ERR_LCD_CALIBRATE -1074395312 // The input image does not seem to be a valid LCD or LED calibration image.
+#define ERR_INVALID_COLOR_SPECTRUM -1074395311 // The color spectrum array you provided has an invalid number of elements or contains an element set to not-a-number (NaN).
+#define ERR_INVALID_PALETTE_TYPE -1074395310 // NI Vision does not support the PaletteType value you supplied.
+#define ERR_INVALID_WINDOW_THREAD_POLICY -1074395309 // NI Vision does not support the WindowThreadPolicy value you supplied.
+#define ERR_INVALID_COLORSENSITIVITY -1074395308 // NI Vision does not support the ColorSensitivity value you supplied.
+#define ERR_PRECISION_NOT_GTR_THAN_0 -1074395307 // The precision parameter must be greater than 0.
+#define ERR_INVALID_TOOL -1074395306 // NI Vision does not support the Tool value you supplied.
+#define ERR_INVALID_REFERENCEMODE -1074395305 // NI Vision does not support the ReferenceMode value you supplied.
+#define ERR_INVALID_MATHTRANSFORMMETHOD -1074395304 // NI Vision does not support the MathTransformMethod value you supplied.
+#define ERR_INVALID_NUM_OF_CLASSES -1074395303 // Invalid number of classes for auto threshold. Acceptable values range from 2 to 256.
+#define ERR_INVALID_THRESHOLDMETHOD -1074395302 // NI Vision does not support the threshold method value you supplied.
+#define ERR_ROI_NOT_2_LINES -1074395301 // The ROI you passed into imaqGetMeterArc must consist of two lines.
+#define ERR_INVALID_METERARCMODE -1074395300 // NI Vision does not support the MeterArcMode value you supplied.
+#define ERR_INVALID_COMPLEXPLANE -1074395299 // NI Vision does not support the ComplexPlane value you supplied.
+#define ERR_COMPLEXPLANE_NOT_REAL_OR_IMAGINARY -1074395298 // You can perform this operation on a real or an imaginary ComplexPlane only.
+#define ERR_INVALID_PARTICLEINFOMODE -1074395297 // NI Vision does not support the ParticleInfoMode value you supplied.
+#define ERR_INVALID_BARCODETYPE -1074395296 // NI Vision does not support the BarcodeType value you supplied.
+#define ERR_INVALID_INTERPOLATIONMETHOD_INTERPOLATEPOINTS -1074395295 // imaqInterpolatePoints does not support the InterpolationMethod value you supplied.
+#define ERR_CONTOUR_INDEX_OUT_OF_RANGE -1074395294 // The contour index you supplied is larger than the number of contours in the ROI.
+#define ERR_CONTOURID_NOT_FOUND -1074395293 // The supplied ContourID did not correlate to a contour inside the ROI.
+#define ERR_POINTS_ARE_COLLINEAR -1074395292 // Do not supply collinear points for this operation.
+#define ERR_SHAPEMATCH_BADIMAGEDATA -1074395291 // Shape Match requires the image to contain only pixel values of 0 or 1.
+#define ERR_SHAPEMATCH_BADTEMPLATE -1074395290 // The template you supplied for ShapeMatch contains no shape information.
+#define ERR_CONTAINER_CAPACITY_EXCEEDED_UINT_MAX -1074395289 // The operation would have exceeded the capacity of an internal container, which is limited to 4294967296 unique elements.
+#define ERR_CONTAINER_CAPACITY_EXCEEDED_INT_MAX -1074395288 // The operation would have exceeded the capacity of an internal container, which is limited to 2147483648 unique elements.
+#define ERR_INVALID_LINE -1074395287 // The line you provided contains two identical points, or one of the coordinate locations for the line is not a number (NaN).
+#define ERR_INVALID_CONCENTRIC_RAKE_DIRECTION -1074395286 // Invalid concentric rake direction.
+#define ERR_INVALID_SPOKE_DIRECTION -1074395285 // Invalid spoke direction.
+#define ERR_INVALID_EDGE_PROCESS -1074395284 // Invalid edge process.
+#define ERR_INVALID_RAKE_DIRECTION -1074395283 // Invalid rake direction.
+#define ERR_CANT_DRAW_INTO_VIEWER -1074395282 // Unable to draw to viewer. You must have the latest version of the control.
+#define ERR_IMAGE_SMALLER_THAN_BORDER -1074395281 // Your image must be larger than its border size for this operation.
+#define ERR_ROI_NOT_RECT -1074395280 // The ROI must only have a single Rectangle contour.
+#define ERR_ROI_NOT_POLYGON -1074395279 // ROI is not a polygon.
+#define ERR_LCD_NOT_NUMERIC -1074395278 // LCD image is not a number.
+#define ERR_BARCODE_CHECKSUM -1074395277 // The decoded barcode information did not pass the checksum test.
+#define ERR_LINES_PARALLEL -1074395276 // You specified parallel lines for the meter ROI.
+#define ERR_INVALID_BROWSER_IMAGE -1074395275 // Invalid browser image.
+#define ERR_DIV_BY_ZERO -1074395270 // Cannot divide by zero.
+#define ERR_NULL_POINTER -1074395269 // Null pointer.
+#define ERR_LINEAR_COEFF -1074395268 // The linear equations are not independent.
+#define ERR_COMPLEX_ROOT -1074395267 // The roots of the equation are complex.
+#define ERR_BARCODE -1074395265 // The barcode does not match the type you specified.
+#define ERR_LCD_NO_SEGMENTS -1074395263 // No lit segment.
+#define ERR_LCD_BAD_MATCH -1074395262 // The LCD does not form a known digit.
+#define ERR_GIP_RANGE -1074395261 // An internal error occurred while attempting to access an invalid coordinate on an image.
+#define ERR_HEAP_TRASHED -1074395260 // An internal memory error occurred.
+#define ERR_BAD_FILTER_WIDTH -1074395258 // The filter width must be odd for the Canny operator.
+#define ERR_INVALID_EDGE_DIR -1074395257 // You supplied an invalid edge direction in the Canny operator.
+#define ERR_EVEN_WINDOW_SIZE -1074395256 // The window size must be odd for the Canny operator.
+#define ERR_INVALID_LEARN_MODE -1074395253 // Invalid learn mode.
+#define ERR_LEARN_SETUP_DATA -1074395252 // Invalid learn setup data.
+#define ERR_INVALID_MATCH_MODE -1074395251 // Invalid match mode.
+#define ERR_MATCH_SETUP_DATA -1074395250 // Invalid match setup data.
+#define ERR_ROTATION_ANGLE_RANGE_TOO_LARGE -1074395249 // At least one range in the array of rotation angle ranges exceeds 360 degrees.
+#define ERR_TOO_MANY_ROTATION_ANGLE_RANGES -1074395248 // The array of rotation angle ranges contains too many ranges.
+#define ERR_TEMPLATE_DESCRIPTOR -1074395247 // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_1 -1074395246 // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_2 -1074395245 // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_3 -1074395244 // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_4 -1074395243 // The template descriptor was created with a newer version of NI Vision. Upgrade to the latest version of NI Vision to use this template.
+#define ERR_TEMPLATE_DESCRIPTOR_ROTATION -1074395242 // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_NOROTATION -1074395241 // The template descriptor does not contain data required for rotation-invariant matching.
+#define ERR_TEMPLATE_DESCRIPTOR_ROTATION_1 -1074395240 // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_SHIFT -1074395239 // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_NOSHIFT -1074395238 // The template descriptor does not contain data required for shift-invariant matching.
+#define ERR_TEMPLATE_DESCRIPTOR_SHIFT_1 -1074395237 // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_NOSCALE -1074395236 // The template descriptor does not contain data required for scale-invariant matching.
+#define ERR_TEMPLATE_IMAGE_CONTRAST_TOO_LOW -1074395235 // The template image does not contain enough contrast.
+#define ERR_TEMPLATE_IMAGE_TOO_SMALL -1074395234 // The template image is too small.
+#define ERR_TEMPLATE_IMAGE_TOO_LARGE -1074395233 // The template image is too large.
+#define ERR_TOO_MANY_OCR_SESSIONS -1074395214 // There are too many OCR sessions open. You must close a session before you can open another one.
+#define ERR_OCR_TEMPLATE_WRONG_SIZE -1074395212 // The size of the template string must match the size of the string you are trying to correct.
+#define ERR_OCR_BAD_TEXT_TEMPLATE -1074395211 // The supplied text template contains nonstandard characters that cannot be generated by OCR.
+#define ERR_OCR_CANNOT_MATCH_TEXT_TEMPLATE -1074395210 // At least one character in the text template was of a lexical class that did not match the supplied character reports.
+#define ERR_OCR_LIB_INIT -1074395203 // The OCR library cannot be initialized correctly.
+#define ERR_OCR_LOAD_LIBRARY -1074395201 // There was a failure when loading one of the internal OCR engine or LabView libraries.
+#define ERR_OCR_INVALID_PARAMETER -1074395200 // One of the parameters supplied to the OCR function that generated this error is invalid.
+#define ERR_MARKER_INFORMATION_NOT_SUPPLIED -1074395199 // Marker image and points are not supplied
+#define ERR_INCOMPATIBLE_MARKER_IMAGE_SIZE -1074395198 // Source Image and Marker Image should be of same size.
+#define ERR_BOTH_MARKER_INPUTS_SUPPLIED -1074395197 // Both Marker Image and Points are supplied.
+#define ERR_INVALID_MORPHOLOGICAL_OPERATION -1074395196 // Invalid Morphological Operation.
+#define ERR_IMAGE_CONTAINS_NAN_VALUES -1074395195 // Float image contains NaN values
+#define ERR_OVERLAY_EXTRAINFO_OPENING_NEW_VERSION -1074395194 // The overlay information you tried to open was created with a newer version of NI Vision. Upgrade to the latest version of NI Vision to read this file.
+#define ERR_NO_CLAMP_FOUND -1074395193 // No valid clamp was found with the current configuration
+#define ERR_NO_CLAMP_WITHIN_ANGLE_RANGE -1074395192 // Supplied angle range for clamp is insufficient
+#define ERR_GHT_INVALID_USE_ALL_CURVES_VALUE -1074395188 // The use all curves advanced option specified during learn is not supported
+#define ERR_INVALID_GAUSS_SIGMA_VALUE -1074395187 // The sigma value specified for the Gaussian filter is too small.
+#define ERR_INVALID_GAUSS_FILTER_TYPE -1074395186 // The specified Gaussian filter type is not supported.
+#define ERR_INVALID_CONTRAST_REVERSAL_MODE -1074395185 // The contrast reversal mode specified during matching is invalid.
+#define ERR_INVALID_ROTATION_RANGE -1074395184 // Invalid roation angle range. The upper bound must be greater than or equal to the lower bound.
+#define ERR_GHT_INVALID_MINIMUM_LEARN_ANGLE_VALUE -1074395183 // The minimum rotation angle value specifed during learning of the template is not supported.
+#define ERR_GHT_INVALID_MAXIMUM_LEARN_ANGLE_VALUE -1074395182 // The maximum rotation angle value specifed during learning of the template is not supported.
+#define ERR_GHT_INVALID_MAXIMUM_LEARN_SCALE_FACTOR -1074395181 // The maximum scale factor specifed during learning of the template is not supported.
+#define ERR_GHT_INVALID_MINIMUM_LEARN_SCALE_FACTOR -1074395180 // The minimum scale factor specifed during learning of the template is not supported.
+#define ERR_OCR_PREPROCESSING_FAILED -1074395179 // The OCR engine failed during the preprocessing stage.
+#define ERR_OCR_RECOGNITION_FAILED -1074395178 // The OCR engine failed during the recognition stage.
+#define ERR_OCR_BAD_USER_DICTIONARY -1074395175 // The provided filename is not valid user dictionary filename.
+#define ERR_OCR_INVALID_AUTOORIENTMODE -1074395174 // NI Vision does not support the AutoOrientMode value you supplied.
+#define ERR_OCR_INVALID_LANGUAGE -1074395173 // NI Vision does not support the Language value you supplied.
+#define ERR_OCR_INVALID_CHARACTERSET -1074395172 // NI Vision does not support the CharacterSet value you supplied.
+#define ERR_OCR_INI_FILE_NOT_FOUND -1074395171 // The system could not locate the initialization file required for OCR initialization.
+#define ERR_OCR_INVALID_CHARACTERTYPE -1074395170 // NI Vision does not support the CharacterType value you supplied.
+#define ERR_OCR_INVALID_RECOGNITIONMODE -1074395169 // NI Vision does not support the RecognitionMode value you supplied.
+#define ERR_OCR_INVALID_AUTOCORRECTIONMODE -1074395168 // NI Vision does not support the AutoCorrectionMode value you supplied.
+#define ERR_OCR_INVALID_OUTPUTDELIMITER -1074395167 // NI Vision does not support the OutputDelimiter value you supplied.
+#define ERR_OCR_BIN_DIR_NOT_FOUND -1074395166 // The system could not locate the OCR binary directory required for OCR initialization.
+#define ERR_OCR_WTS_DIR_NOT_FOUND -1074395165 // The system could not locate the OCR weights directory required for OCR initialization.
+#define ERR_OCR_ADD_WORD_FAILED -1074395164 // The supplied word could not be added to the user dictionary.
+#define ERR_OCR_INVALID_CHARACTERPREFERENCE -1074395163 // NI Vision does not support the CharacterPreference value you supplied.
+#define ERR_OCR_INVALID_CORRECTIONMODE -1074395162 // NI Vision does not support the CorrectionMethod value you supplied.
+#define ERR_OCR_INVALID_CORRECTIONLEVEL -1074395161 // NI Vision does not support the CorrectionLevel value you supplied.
+#define ERR_OCR_INVALID_MAXPOINTSIZE -1074395160 // NI Vision does not support the maximum point size you supplied. Valid values range from 4 to 72.
+#define ERR_OCR_INVALID_TOLERANCE -1074395159 // NI Vision does not support the tolerance value you supplied. Valid values are non-negative.
+#define ERR_OCR_INVALID_CONTRASTMODE -1074395158 // NI Vision does not support the ContrastMode value you supplied.
+#define ERR_OCR_SKEW_DETECT_FAILED -1074395156 // The OCR attempted to detected the text skew and failed.
+#define ERR_OCR_ORIENT_DETECT_FAILED -1074395155 // The OCR attempted to detected the text orientation and failed.
+#define ERR_FONT_FILE_FORMAT -1074395153 // Invalid font file format.
+#define ERR_FONT_FILE_NOT_FOUND -1074395152 // Font file not found.
+#define ERR_OCR_CORRECTION_FAILED -1074395151 // The OCR engine failed during the correction stage.
+#define ERR_INVALID_ROUNDING_MODE -1074395150 // NI Vision does not support the RoundingMode value you supplied.
+#define ERR_DUPLICATE_TRANSFORM_TYPE -1074395149 // Found a duplicate transform type in the properties array. Each properties array may only contain one behavior for each transform type.
+#define ERR_OVERLAY_GROUP_NOT_FOUND -1074395148 // Overlay Group Not Found.
+#define ERR_BARCODE_RSSLIMITED -1074395147 // The barcode is not a valid RSS Limited symbol
+#define ERR_QR_DETECTION_VERSION -1074395146 // Couldn't determine the correct version of the QR code.
+#define ERR_QR_INVALID_READ -1074395145 // Invalid read of the QR code.
+#define ERR_QR_INVALID_BARCODE -1074395144 // The barcode that was read contains invalid parameters.
+#define ERR_QR_DETECTION_MODE -1074395143 // The data stream that was demodulated could not be read because the mode was not detected.
+#define ERR_QR_DETECTION_MODELTYPE -1074395142 // Couldn't determine the correct model of the QR code.
+#define ERR_OCR_NO_TEXT_FOUND -1074395141 // The OCR engine could not find any text in the supplied region.
+#define ERR_OCR_CHAR_REPORT_CORRUPTED -1074395140 // One of the character reports is no longer usable by the system.
+#define ERR_IMAQ_QR_DIMENSION_INVALID -1074395139 // Invalid Dimensions.
+#define ERR_OCR_REGION_TOO_SMALL -1074395138 // The OCR region provided was too small to have contained any characters.
+#define _FIRST_ERR ERR_SYSTEM_ERROR
+#define _LAST_ERR ERR_OCR_REGION_TOO_SMALL
+
+//============================================================================
+// Enumerated Types
+//============================================================================
+typedef enum PointSymbol_enum {
+ IMAQ_POINT_AS_PIXEL = 0, //A single pixel represents a point in the overlay.
+ IMAQ_POINT_AS_CROSS = 1, //A cross represents a point in the overlay.
+ IMAQ_POINT_USER_DEFINED = 2, //The pattern supplied by the user represents a point in the overlay.
+ IMAQ_POINT_SYMBOL_SIZE_GUARD = 0xFFFFFFFF
+} PointSymbol;
+
+typedef enum MeasurementValue_enum {
+ IMAQ_AREA = 0, //Surface area of the particle in pixels.
+ IMAQ_AREA_CALIBRATED = 1, //Surface area of the particle in calibrated units.
+ IMAQ_NUM_HOLES = 2, //Number of holes in the particle.
+ IMAQ_AREA_OF_HOLES = 3, //Surface area of the holes in calibrated units.
+ IMAQ_TOTAL_AREA = 4, //Total surface area (holes and particle) in calibrated units.
+ IMAQ_IMAGE_AREA = 5, //Surface area of the entire image in calibrated units.
+ IMAQ_PARTICLE_TO_IMAGE = 6, //Ratio, expressed as a percentage, of the surface area of a particle in relation to the total area of the particle.
+ IMAQ_PARTICLE_TO_TOTAL = 7, //Ratio, expressed as a percentage, of the surface area of a particle in relation to the total area of the particle.
+ IMAQ_CENTER_MASS_X = 8, //X-coordinate of the center of mass.
+ IMAQ_CENTER_MASS_Y = 9, //Y-coordinate of the center of mass.
+ IMAQ_LEFT_COLUMN = 10, //Left edge of the bounding rectangle.
+ IMAQ_TOP_ROW = 11, //Top edge of the bounding rectangle.
+ IMAQ_RIGHT_COLUMN = 12, //Right edge of the bounding rectangle.
+ IMAQ_BOTTOM_ROW = 13, //Bottom edge of bounding rectangle.
+ IMAQ_WIDTH = 14, //Width of bounding rectangle in calibrated units.
+ IMAQ_HEIGHT = 15, //Height of bounding rectangle in calibrated units.
+ IMAQ_MAX_SEGMENT_LENGTH = 16, //Length of longest horizontal line segment.
+ IMAQ_MAX_SEGMENT_LEFT_COLUMN = 17, //Leftmost x-coordinate of longest horizontal line segment.
+ IMAQ_MAX_SEGMENT_TOP_ROW = 18, //Y-coordinate of longest horizontal line segment.
+ IMAQ_PERIMETER = 19, //Outer perimeter of the particle.
+ IMAQ_PERIMETER_OF_HOLES = 20, //Perimeter of all holes within the particle.
+ IMAQ_SIGMA_X = 21, //Sum of the particle pixels on the x-axis.
+ IMAQ_SIGMA_Y = 22, //Sum of the particle pixels on the y-axis.
+ IMAQ_SIGMA_XX = 23, //Sum of the particle pixels on the x-axis squared.
+ IMAQ_SIGMA_YY = 24, //Sum of the particle pixels on the y-axis squared.
+ IMAQ_SIGMA_XY = 25, //Sum of the particle pixels on the x-axis and y-axis.
+ IMAQ_PROJ_X = 26, //Projection corrected in X.
+ IMAQ_PROJ_Y = 27, //Projection corrected in Y.
+ IMAQ_INERTIA_XX = 28, //Inertia matrix coefficient in XX.
+ IMAQ_INERTIA_YY = 29, //Inertia matrix coefficient in YY.
+ IMAQ_INERTIA_XY = 30, //Inertia matrix coefficient in XY.
+ IMAQ_MEAN_H = 31, //Mean length of horizontal segments.
+ IMAQ_MEAN_V = 32, //Mean length of vertical segments.
+ IMAQ_MAX_INTERCEPT = 33, //Length of longest segment of the convex hull.
+ IMAQ_MEAN_INTERCEPT = 34, //Mean length of the chords in an object perpendicular to its max intercept.
+ IMAQ_ORIENTATION = 35, //The orientation based on the inertia of the pixels in the particle.
+ IMAQ_EQUIV_ELLIPSE_MINOR = 36, //Total length of the axis of the ellipse having the same area as the particle and a major axis equal to half the max intercept.
+ IMAQ_ELLIPSE_MAJOR = 37, //Total length of major axis having the same area and perimeter as the particle in calibrated units.
+ IMAQ_ELLIPSE_MINOR = 38, //Total length of minor axis having the same area and perimeter as the particle in calibrated units.
+ IMAQ_ELLIPSE_RATIO = 39, //Fraction of major axis to minor axis.
+ IMAQ_RECT_LONG_SIDE = 40, //Length of the long side of a rectangle having the same area and perimeter as the particle in calibrated units.
+ IMAQ_RECT_SHORT_SIDE = 41, //Length of the short side of a rectangle having the same area and perimeter as the particle in calibrated units.
+ IMAQ_RECT_RATIO = 42, //Ratio of rectangle long side to rectangle short side.
+ IMAQ_ELONGATION = 43, //Max intercept/mean perpendicular intercept.
+ IMAQ_COMPACTNESS = 44, //Particle area/(height x width).
+ IMAQ_HEYWOOD = 45, //Particle perimeter/perimeter of the circle having the same area as the particle.
+ IMAQ_TYPE_FACTOR = 46, //A complex factor relating the surface area to the moment of inertia.
+ IMAQ_HYDRAULIC = 47, //Particle area/particle perimeter.
+ IMAQ_WADDLE_DISK = 48, //Diameter of the disk having the same area as the particle in user units.
+ IMAQ_DIAGONAL = 49, //Diagonal of an equivalent rectangle in user units.
+ IMAQ_MEASUREMENT_VALUE_SIZE_GUARD = 0xFFFFFFFF
+} MeasurementValue;
+
+typedef enum ScalingMode_enum {
+ IMAQ_SCALE_LARGER = 0, //The function duplicates pixels to make the image larger.
+ IMAQ_SCALE_SMALLER = 1, //The function subsamples pixels to make the image smaller.
+ IMAQ_SCALING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ScalingMode;
+
+typedef enum ScalingMethod_enum {
+ IMAQ_SCALE_TO_PRESERVE_AREA = 0, //Correction functions scale the image such that the features in the corrected image have the same area as the features in the input image.
+ IMAQ_SCALE_TO_FIT = 1, //Correction functions scale the image such that the corrected image is the same size as the input image.
+ IMAQ_SCALING_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} ScalingMethod;
+
+typedef enum ReferenceMode_enum {
+ IMAQ_COORD_X_Y = 0, //This method requires three elements in the points array.
+ IMAQ_COORD_ORIGIN_X = 1, //This method requires two elements in the points array.
+ IMAQ_REFERENCE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ReferenceMode;
+
+typedef enum RectOrientation_enum {
+ IMAQ_BASE_INSIDE = 0, //Specifies that the base of the rectangular image lies along the inside edge of the annulus.
+ IMAQ_BASE_OUTSIDE = 1, //Specifies that the base of the rectangular image lies along the outside edge of the annulus.
+ IMAQ_TEXT_ORIENTATION_SIZE_GUARD = 0xFFFFFFFF
+} RectOrientation;
+
+typedef enum ShapeMode_enum {
+ IMAQ_SHAPE_RECT = 1, //The function draws a rectangle.
+ IMAQ_SHAPE_OVAL = 2, //The function draws an oval.
+ IMAQ_SHAPE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ShapeMode;
+
+typedef enum PolarityType_enum {
+ IMAQ_EDGE_RISING = 1, //The edge is a rising edge.
+ IMAQ_EDGE_FALLING = -1, //The edge is a falling edge.
+ IMAQ_POLARITY_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} PolarityType;
+
+typedef enum SizeType_enum {
+ IMAQ_KEEP_LARGE = 0, //The function keeps large particles remaining after the erosion.
+ IMAQ_KEEP_SMALL = 1, //The function keeps small particles eliminated by the erosion.
+ IMAQ_SIZE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} SizeType;
+
+typedef enum Plane3D_enum {
+ IMAQ_3D_REAL = 0, //The function shows the real part of complex images.
+ IMAQ_3D_IMAGINARY = 1, //The function shows the imaginary part of complex images.
+ IMAQ_3D_MAGNITUDE = 2, //The function shows the magnitude part of complex images.
+ IMAQ_3D_PHASE = 3, //The function shows the phase part of complex images.
+ IMAQ_PLANE_3D_SIZE_GUARD = 0xFFFFFFFF
+} Plane3D;
+
+typedef enum PhotometricMode_enum {
+ IMAQ_WHITE_IS_ZERO = 0, //The function interprets zero-value pixels as white.
+ IMAQ_BLACK_IS_ZERO = 1, //The function interprets zero-value pixels as black.
+ IMAQ_PHOTOMETRIC_MODE_SIZE_GUARD = 0xFFFFFFFF
+} PhotometricMode;
+
+typedef enum ParticleInfoMode_enum {
+ IMAQ_BASIC_INFO = 0, //The function returns only the following elements of each report: area, calibratedArea, boundingRect.
+ IMAQ_ALL_INFO = 1, //The function returns all the information about each particle.
+ IMAQ_PARTICLE_INFO_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ParticleInfoMode;
+
+typedef enum OutlineMethod_enum {
+ IMAQ_EDGE_DIFFERENCE = 0, //The function uses a method that produces continuous contours by highlighting each pixel where an intensity variation occurs between itself and its three upper-left neighbors.
+ IMAQ_EDGE_GRADIENT = 1, //The function uses a method that outlines contours where an intensity variation occurs along the vertical axis.
+ IMAQ_EDGE_PREWITT = 2, //The function uses a method that extracts the outer contours of objects.
+ IMAQ_EDGE_ROBERTS = 3, //The function uses a method that outlines the contours that highlight pixels where an intensity variation occurs along the diagonal axes.
+ IMAQ_EDGE_SIGMA = 4, //The function uses a method that outlines contours and details by setting pixels to the mean value found in their neighborhood, if their deviation from this value is not significant.
+ IMAQ_EDGE_SOBEL = 5, //The function uses a method that extracts the outer contours of objects.
+ IMAQ_OUTLINE_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} OutlineMethod;
+
+typedef enum MorphologyMethod_enum {
+ IMAQ_AUTOM = 0, //The function uses a transformation that generates simpler particles that contain fewer details.
+ IMAQ_CLOSE = 1, //The function uses a transformation that fills tiny holes and smooths boundaries.
+ IMAQ_DILATE = 2, //The function uses a transformation that eliminates tiny holes isolated in particles and expands the contour of the particles according to the template defined by the structuring element.
+ IMAQ_ERODE = 3, //The function uses a transformation that eliminates pixels isolated in the background and erodes the contour of particles according to the template defined by the structuring element.
+ IMAQ_GRADIENT = 4, //The function uses a transformation that leaves only the pixels that would be added by the dilation process or eliminated by the erosion process.
+ IMAQ_GRADIENTOUT = 5, //The function uses a transformation that leaves only the pixels that would be added by the dilation process.
+ IMAQ_GRADIENTIN = 6, //The function uses a transformation that leaves only the pixels that would be eliminated by the erosion process.
+ IMAQ_HITMISS = 7, //The function uses a transformation that extracts each pixel located in a neighborhood exactly matching the template defined by the structuring element.
+ IMAQ_OPEN = 8, //The function uses a transformation that removes small particles and smooths boundaries.
+ IMAQ_PCLOSE = 9, //The function uses a transformation that fills tiny holes and smooths the inner contour of particles according to the template defined by the structuring element.
+ IMAQ_POPEN = 10, //The function uses a transformation that removes small particles and smooths the contour of particles according to the template defined by the structuring element.
+ IMAQ_THICK = 11, //The function uses a transformation that adds to an image those pixels located in a neighborhood that matches a template specified by the structuring element.
+ IMAQ_THIN = 12, //The function uses a transformation that eliminates pixels that are located in a neighborhood matching a template specified by the structuring element.
+ IMAQ_MORPHOLOGY_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} MorphologyMethod;
+
+typedef enum MeterArcMode_enum {
+ IMAQ_METER_ARC_ROI = 0, //The function uses the roi parameter and ignores the base, start, and end parameters.
+ IMAQ_METER_ARC_POINTS = 1, //The function uses the base,start, and end parameters and ignores the roi parameter.
+ IMAQ_METER_ARC_MODE_SIZE_GUARD = 0xFFFFFFFF
+} MeterArcMode;
+
+typedef enum RakeDirection_enum {
+ IMAQ_LEFT_TO_RIGHT = 0, //The function searches from the left side of the search area to the right side of the search area.
+ IMAQ_RIGHT_TO_LEFT = 1, //The function searches from the right side of the search area to the left side of the search area.
+ IMAQ_TOP_TO_BOTTOM = 2, //The function searches from the top side of the search area to the bottom side of the search area.
+ IMAQ_BOTTOM_TO_TOP = 3, //The function searches from the bottom side of the search area to the top side of the search area.
+ IMAQ_RAKE_DIRECTION_SIZE_GUARD = 0xFFFFFFFF
+} RakeDirection;
+
+typedef enum TruncateMode_enum {
+ IMAQ_TRUNCATE_LOW = 0, //The function truncates low frequencies.
+ IMAQ_TRUNCATE_HIGH = 1, //The function truncates high frequencies.
+ IMAQ_TRUNCATE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} TruncateMode;
+
+typedef enum AttenuateMode_enum {
+ IMAQ_ATTENUATE_LOW = 0, //The function attenuates low frequencies.
+ IMAQ_ATTENUATE_HIGH = 1, //The function attenuates high frequencies.
+ IMAQ_ATTENUATE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} AttenuateMode;
+
+typedef enum WindowThreadPolicy_enum {
+ IMAQ_CALLING_THREAD = 0, //Using this policy, NI Vision creates windows in the thread that makes the first display function call for a given window number.
+ IMAQ_SEPARATE_THREAD = 1, //Using this policy, NI Vision creates windows in a separate thread and processes messages for the windows automatically.
+ IMAQ_WINDOW_THREAD_POLICY_SIZE_GUARD = 0xFFFFFFFF
+} WindowThreadPolicy;
+
+typedef enum WindowOptions_enum {
+ IMAQ_WIND_RESIZABLE = 1, //When present, the user may resize the window interactively.
+ IMAQ_WIND_TITLEBAR = 2, //When present, the title bar on the window is visible.
+ IMAQ_WIND_CLOSEABLE = 4, //When present, the close box is available.
+ IMAQ_WIND_TOPMOST = 8, //When present, the window is always on top.
+ IMAQ_WINDOW_OPTIONS_SIZE_GUARD = 0xFFFFFFFF
+} WindowOptions;
+
+typedef enum WindowEventType_enum {
+ IMAQ_NO_EVENT = 0, //No event occurred since the last call to imaqGetLastEvent().
+ IMAQ_CLICK_EVENT = 1, //The user clicked on a window.
+ IMAQ_DRAW_EVENT = 2, //The user drew an ROI in a window.
+ IMAQ_MOVE_EVENT = 3, //The user moved a window.
+ IMAQ_SIZE_EVENT = 4, //The user sized a window.
+ IMAQ_SCROLL_EVENT = 5, //The user scrolled a window.
+ IMAQ_ACTIVATE_EVENT = 6, //The user activated a window.
+ IMAQ_CLOSE_EVENT = 7, //The user closed a window.
+ IMAQ_DOUBLE_CLICK_EVENT = 8, //The user double-clicked in a window.
+ IMAQ_WINDOW_EVENT_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} WindowEventType;
+
+typedef enum VisionInfoType_enum {
+ IMAQ_ANY_VISION_INFO = 0, //The function checks if any extra vision information is associated with the image.
+ IMAQ_PATTERN_MATCHING_INFO = 1, //The function checks if any pattern matching template information is associated with the image.
+ IMAQ_CALIBRATION_INFO = 2, //The function checks if any calibration information is associated with the image.
+ IMAQ_OVERLAY_INFO = 3, //The function checks if any overlay information is associated with the image.
+ IMAQ_VISION_INFO_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} VisionInfoType;
+
+typedef enum SearchStrategy_enum {
+ IMAQ_CONSERVATIVE = 1, //Instructs the pattern matching algorithm to use the largest possible amount of information from the image at the expense of slowing down the speed of the algorithm.
+ IMAQ_BALANCED = 2, //Instructs the pattern matching algorithm to balance the amount of information from the image it uses with the speed of the algorithm.
+ IMAQ_AGGRESSIVE = 3, //Instructs the pattern matching algorithm to use a lower amount of information from the image, which allows the algorithm to run quickly but at the expense of accuracy.
+ IMAQ_VERY_AGGRESSIVE = 4, //Instructs the pattern matching algorithm to use the smallest possible amount of information from the image, which allows the algorithm to run at the highest speed possible but at the expense of accuracy.
+ IMAQ_SEARCH_STRATEGY_SIZE_GUARD = 0xFFFFFFFF
+} SearchStrategy;
+
+typedef enum TwoEdgePolarityType_enum {
+ IMAQ_NONE = 0, //The function ignores the polarity of the edges.
+ IMAQ_RISING_FALLING = 1, //The polarity of the first edge is rising (dark to light) and the polarity of the second edge is falling (light to dark).
+ IMAQ_FALLING_RISING = 2, //The polarity of the first edge is falling (light to dark) and the polarity of the second edge is rising (dark to light).
+ IMAQ_RISING_RISING = 3, //The polarity of the first edge is rising (dark to light) and the polarity of the second edge is rising (dark to light).
+ IMAQ_FALLING_FALLING = 4, //The polarity of the first edge is falling (light to dark) and the polarity of the second edge is falling (light to dark).
+ IMAQ_TWO_EDGE_POLARITY_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} TwoEdgePolarityType;
+
+typedef enum ObjectType_enum {
+ IMAQ_BRIGHT_OBJECTS = 0, //The function detects bright objects.
+ IMAQ_DARK_OBJECTS = 1, //The function detects dark objects.
+ IMAQ_OBJECT_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ObjectType;
+
+typedef enum Tool_enum {
+ IMAQ_NO_TOOL = -1, //No tool is in the selected state.
+ IMAQ_SELECTION_TOOL = 0, //The selection tool selects an existing ROI in an image.
+ IMAQ_POINT_TOOL = 1, //The point tool draws a point on the image.
+ IMAQ_LINE_TOOL = 2, //The line tool draws a line on the image.
+ IMAQ_RECTANGLE_TOOL = 3, //The rectangle tool draws a rectangle on the image.
+ IMAQ_OVAL_TOOL = 4, //The oval tool draws an oval on the image.
+ IMAQ_POLYGON_TOOL = 5, //The polygon tool draws a polygon on the image.
+ IMAQ_CLOSED_FREEHAND_TOOL = 6, //The closed freehand tool draws closed freehand shapes on the image.
+ IMAQ_ANNULUS_TOOL = 7, //The annulus tool draws annuluses on the image.
+ IMAQ_ZOOM_TOOL = 8, //The zoom tool controls the zoom of an image.
+ IMAQ_PAN_TOOL = 9, //The pan tool shifts the view of the image.
+ IMAQ_POLYLINE_TOOL = 10, //The polyline tool draws a series of connected straight lines on the image.
+ IMAQ_FREEHAND_TOOL = 11, //The freehand tool draws freehand lines on the image.
+ IMAQ_ROTATED_RECT_TOOL = 12, //The rotated rectangle tool draws rotated rectangles on the image.
+ IMAQ_ZOOM_OUT_TOOL = 13, //The zoom out tool controls the zoom of an image.
+ IMAQ_TOOL_SIZE_GUARD = 0xFFFFFFFF
+} Tool;
+
+typedef enum TIFFCompressionType_enum {
+ IMAQ_NO_COMPRESSION = 0, //The function does not compress the TIFF file.
+ IMAQ_JPEG = 1, //The function uses the JPEG compression algorithm to compress the TIFF file.
+ IMAQ_RUN_LENGTH = 2, //The function uses a run length compression algorithm to compress the TIFF file.
+ IMAQ_ZIP = 3, //The function uses the ZIP compression algorithm to compress the TIFF file.
+ IMAQ_TIFF_COMPRESSION_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} TIFFCompressionType;
+
+typedef enum ThresholdMethod_enum {
+ IMAQ_THRESH_CLUSTERING = 0, //The function uses a method that sorts the histogram of the image within a discrete number of classes corresponding to the number of phases perceived in an image.
+ IMAQ_THRESH_ENTROPY = 1, //The function uses a method that is best for detecting particles that are present in minuscule proportions on the image.
+ IMAQ_THRESH_METRIC = 2, //The function uses a method that is well-suited for images in which classes are not too disproportionate.
+ IMAQ_THRESH_MOMENTS = 3, //The function uses a method that is suited for images that have poor contrast.
+ IMAQ_THRESH_INTERCLASS = 4, //The function uses a method that is well-suited for images in which classes have well separated pixel value distributions.
+ IMAQ_THRESHOLD_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} ThresholdMethod;
+
+typedef enum TextAlignment_enum {
+ IMAQ_LEFT = 0, //Left aligns the text at the reference point.
+ IMAQ_CENTER = 1, //Centers the text around the reference point.
+ IMAQ_RIGHT = 2, //Right aligns the text at the reference point.
+ IMAQ_TEXT_ALIGNMENT_SIZE_GUARD = 0xFFFFFFFF
+} TextAlignment;
+
+typedef enum SpokeDirection_enum {
+ IMAQ_OUTSIDE_TO_INSIDE = 0, //The function searches from the outside of the search area to the inside of the search area.
+ IMAQ_INSIDE_TO_OUTSIDE = 1, //The function searches from the inside of the search area to the outside of the search area.
+ IMAQ_SPOKE_DIRECTION_SIZE_GUARD = 0xFFFFFFFF
+} SpokeDirection;
+
+typedef enum SkeletonMethod_enum {
+ IMAQ_SKELETON_L = 0, //Uses an L-shaped structuring element in the skeleton function.
+ IMAQ_SKELETON_M = 1, //Uses an M-shaped structuring element in the skeleton function.
+ IMAQ_SKELETON_INVERSE = 2, //Uses an L-shaped structuring element on an inverse of the image in the skeleton function.
+ IMAQ_SKELETON_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} SkeletonMethod;
+
+typedef enum VerticalTextAlignment_enum {
+ IMAQ_BOTTOM = 0, //Aligns the bottom of the text at the reference point.
+ IMAQ_TOP = 1, //Aligns the top of the text at the reference point.
+ IMAQ_BASELINE = 2, //Aligns the baseline of the text at the reference point.
+ IMAQ_VERTICAL_TEXT_ALIGNMENT_SIZE_GUARD = 0xFFFFFFFF
+} VerticalTextAlignment;
+
+typedef enum CalibrationROI_enum {
+ IMAQ_FULL_IMAGE = 0, //The correction function corrects the whole image, regardless of the user-defined or calibration-defined ROIs.
+ IMAQ_CALIBRATION_ROI = 1, //The correction function corrects the area defined by the calibration ROI.
+ IMAQ_USER_ROI = 2, //The correction function corrects the area defined by the user-defined ROI.
+ IMAQ_CALIBRATION_AND_USER_ROI = 3, //The correction function corrects the area defined by the intersection of the user-defined ROI and the calibration ROI.
+ IMAQ_CALIBRATION_OR_USER_ROI = 4, //The correction function corrects the area defined by the union of the user-defined ROI and the calibration ROI.
+ IMAQ_CALIBRATION_ROI_SIZE_GUARD = 0xFFFFFFFF
+} CalibrationROI;
+
+typedef enum ContourType_enum {
+ IMAQ_EMPTY_CONTOUR = 0, //The contour is empty.
+ IMAQ_POINT = 1, //The contour represents a point.
+ IMAQ_LINE = 2, //The contour represents a line.
+ IMAQ_RECT = 3, //The contour represents a rectangle.
+ IMAQ_OVAL = 4, //The contour represents an oval.
+ IMAQ_CLOSED_CONTOUR = 5, //The contour represents a series of connected points where the last point connects to the first.
+ IMAQ_OPEN_CONTOUR = 6, //The contour represents a series of connected points where the last point does not connect to the first.
+ IMAQ_ANNULUS = 7, //The contour represents an annulus.
+ IMAQ_ROTATED_RECT = 8, //The contour represents a rotated rectangle.
+ IMAQ_CONTOUR_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ContourType;
+
+typedef enum MathTransformMethod_enum {
+ IMAQ_TRANSFORM_LINEAR = 0, //The function uses linear remapping.
+ IMAQ_TRANSFORM_LOG = 1, //The function uses logarithmic remapping.
+ IMAQ_TRANSFORM_EXP = 2, //The function uses exponential remapping.
+ IMAQ_TRANSFORM_SQR = 3, //The function uses square remapping.
+ IMAQ_TRANSFORM_SQRT = 4, //The function uses square root remapping.
+ IMAQ_TRANSFORM_POWX = 5, //The function uses power X remapping.
+ IMAQ_TRANSFORM_POW1X = 6, //The function uses power 1/X remapping.
+ IMAQ_MATH_TRANSFORM_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} MathTransformMethod;
+
+typedef enum ComplexPlane_enum {
+ IMAQ_REAL = 0, //The function operates on the real plane of the complex image.
+ IMAQ_IMAGINARY = 1, //The function operates on the imaginary plane of the complex image.
+ IMAQ_MAGNITUDE = 2, //The function operates on the magnitude plane of the complex image.
+ IMAQ_PHASE = 3, //The function operates on the phase plane of the complex image.
+ IMAQ_COMPLEX_PLANE_SIZE_GUARD = 0xFFFFFFFF
+} ComplexPlane;
+
+typedef enum PaletteType_enum {
+ IMAQ_PALETTE_GRAY = 0, //The function uses a palette that has a gradual gray-level variation from black to white.
+ IMAQ_PALETTE_BINARY = 1, //The function uses a palette of 16 cycles of 16 different colors that is useful with binary images.
+ IMAQ_PALETTE_GRADIENT = 2, //The function uses a palette that has a gradation from red to white with a prominent range of light blue in the upper value range.
+ IMAQ_PALETTE_RAINBOW = 3, //The function uses a palette that has a gradation from blue to red with a prominent range of greens in the middle value range.
+ IMAQ_PALETTE_TEMPERATURE = 4, //The function uses a palette that has a gradation from light brown to dark brown.
+ IMAQ_PALETTE_USER = 5, //The function uses a palette defined by the user.
+ IMAQ_PALETTE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} PaletteType;
+
+typedef enum ColorSensitivity_enum {
+ IMAQ_SENSITIVITY_LOW = 0, //Instructs the algorithm to divide the hue plane into a low number of sectors, allowing for simple color analysis.
+ IMAQ_SENSITIVITY_MED = 1, //Instructs the algorithm to divide the hue plane into a medium number of sectors, allowing for color analysis that balances sensitivity and complexity.
+ IMAQ_SENSITIVITY_HIGH = 2, //Instructs the algorithm to divide the hue plane into a high number of sectors, allowing for complex, sensitive color analysis.
+ IMAQ_COLOR_SENSITIVITY_SIZE_GUARD = 0xFFFFFFFF
+} ColorSensitivity;
+
+typedef enum ColorMode_enum {
+ IMAQ_RGB = 0, //The function operates in the RGB (Red, Blue, Green) color space.
+ IMAQ_HSL = 1, //The function operates in the HSL (Hue, Saturation, Luminance) color space.
+ IMAQ_HSV = 2, //The function operates in the HSV (Hue, Saturation, Value) color space.
+ IMAQ_HSI = 3, //The function operates in the HSI (Hue, Saturation, Intensity) color space.
+ IMAQ_CIE = 4, //The function operates in the CIE L*a*b* color space.
+ IMAQ_CIEXYZ = 5, //The function operates in the CIE XYZ color space.
+ IMAQ_COLOR_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ColorMode;
+
+typedef enum DetectionMode_enum {
+ IMAQ_DETECT_PEAKS = 0, //The function detects peaks.
+ IMAQ_DETECT_VALLEYS = 1, //The function detects valleys.
+ IMAQ_DETECTION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DetectionMode;
+
+typedef enum CalibrationUnit_enum {
+ IMAQ_UNDEFINED = 0, //The image does not have a defined unit of measurement.
+ IMAQ_ANGSTROM = 1, //The unit of measure for the image is angstroms.
+ IMAQ_MICROMETER = 2, //The unit of measure for the image is micrometers.
+ IMAQ_MILLIMETER = 3, //The unit of measure for the image is millimeters.
+ IMAQ_CENTIMETER = 4, //The unit of measure for the image is centimeters.
+ IMAQ_METER = 5, //The unit of measure for the image is meters.
+ IMAQ_KILOMETER = 6, //The unit of measure for the image is kilometers.
+ IMAQ_MICROINCH = 7, //The unit of measure for the image is microinches.
+ IMAQ_INCH = 8, //The unit of measure for the image is inches.
+ IMAQ_FOOT = 9, //The unit of measure for the image is feet.
+ IMAQ_NAUTICMILE = 10, //The unit of measure for the image is nautical miles.
+ IMAQ_GROUNDMILE = 11, //The unit of measure for the image is ground miles.
+ IMAQ_STEP = 12, //The unit of measure for the image is steps.
+ IMAQ_CALIBRATION_UNIT_SIZE_GUARD = 0xFFFFFFFF
+} CalibrationUnit;
+
+typedef enum ConcentricRakeDirection_enum {
+ IMAQ_COUNTER_CLOCKWISE = 0, //The function searches the search area in a counter-clockwise direction.
+ IMAQ_CLOCKWISE = 1, //The function searches the search area in a clockwise direction.
+ IMAQ_CONCENTRIC_RAKE_DIRECTION_SIZE_GUARD = 0xFFFFFFFF
+} ConcentricRakeDirection;
+
+typedef enum CalibrationMode_enum {
+ IMAQ_PERSPECTIVE = 0, //Functions correct for distortion caused by the camera's perspective.
+ IMAQ_NONLINEAR = 1, //Functions correct for distortion caused by the camera's lens.
+ IMAQ_SIMPLE_CALIBRATION = 2, //Functions do not correct for distortion.
+ IMAQ_CORRECTED_IMAGE = 3, //The image is already corrected.
+ IMAQ_CALIBRATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} CalibrationMode;
+
+typedef enum BrowserLocation_enum {
+ IMAQ_INSERT_FIRST_FREE = 0, //Inserts the thumbnail in the first available cell.
+ IMAQ_INSERT_END = 1, //Inserts the thumbnail after the last occupied cell.
+ IMAQ_BROWSER_LOCATION_SIZE_GUARD = 0xFFFFFFFF
+} BrowserLocation;
+
+typedef enum BrowserFrameStyle_enum {
+ IMAQ_RAISED_FRAME = 0, //Each thumbnail has a raised frame.
+ IMAQ_BEVELLED_FRAME = 1, //Each thumbnail has a beveled frame.
+ IMAQ_OUTLINE_FRAME = 2, //Each thumbnail has an outlined frame.
+ IMAQ_HIDDEN_FRAME = 3, //Each thumbnail has a hidden frame.
+ IMAQ_STEP_FRAME = 4, //Each thumbnail has a stepped frame.
+ IMAQ_RAISED_OUTLINE_FRAME = 5, //Each thumbnail has a raised, outlined frame.
+ IMAQ_BROWSER_FRAME_STYLE_SIZE_GUARD = 0xFFFFFFFF
+} BrowserFrameStyle;
+
+typedef enum BorderMethod_enum {
+ IMAQ_BORDER_MIRROR = 0, //Symmetrically copies pixel values from the image into the border.
+ IMAQ_BORDER_COPY = 1, //Copies the value of the pixel closest to the edge of the image into the border.
+ IMAQ_BORDER_CLEAR = 2, //Sets all pixels in the border to 0.
+ IMAQ_BORDER_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} BorderMethod;
+
+typedef enum BarcodeType_enum {
+ IMAQ_INVALID = -1, //The barcode is not of a type known by NI Vision.
+ IMAQ_CODABAR = 1, //The barcode is of type Codabar.
+ IMAQ_CODE39 = 2, //The barcode is of type Code 39.
+ IMAQ_CODE93 = 4, //The barcode is of type Code 93.
+ IMAQ_CODE128 = 8, //The barcode is of type Code 128.
+ IMAQ_EAN8 = 16, //The barcode is of type EAN 8.
+ IMAQ_EAN13 = 32, //The barcode is of type EAN 13.
+ IMAQ_I2_OF_5 = 64, //The barcode is of type Code 25.
+ IMAQ_MSI = 128, //The barcode is of type MSI code.
+ IMAQ_UPCA = 256, //The barcode is of type UPC A.
+ IMAQ_PHARMACODE = 512, //The barcode is of type Pharmacode.
+ IMAQ_RSS_LIMITED = 1024, //The barcode is of type RSS Limited.
+ IMAQ_BARCODE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} BarcodeType;
+
+typedef enum AxisOrientation_enum {
+ IMAQ_DIRECT = 0, //The y-axis direction corresponds to the y-axis direction of the Cartesian coordinate system.
+ IMAQ_INDIRECT = 1, //The y-axis direction corresponds to the y-axis direction of an image.
+ IMAQ_AXIS_ORIENTATION_SIZE_GUARD = 0xFFFFFFFF
+} AxisOrientation;
+
+typedef enum ColorIgnoreMode_enum {
+ IMAQ_IGNORE_NONE = 0, //Specifies that the function does not ignore any pixels.
+ IMAQ_IGNORE_BLACK = 1, //Specifies that the function ignores black pixels.
+ IMAQ_IGNORE_WHITE = 2, //Specifies that the function ignores white pixels.
+ IMAQ_IGNORE_BLACK_AND_WHITE = 3, //Specifies that the function ignores black pixels and white pixels.
+ IMAQ_BLACK_WHITE_IGNORE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ColorIgnoreMode;
+
+typedef enum LevelType_enum {
+ IMAQ_ABSOLUTE = 0, //The function evaluates the threshold and hysteresis values as absolute values.
+ IMAQ_RELATIVE = 1, //The function evaluates the threshold and hysteresis values relative to the dynamic range of the given path.
+ IMAQ_LEVEL_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} LevelType;
+
+typedef enum MatchingMode_enum {
+ IMAQ_MATCH_SHIFT_INVARIANT = 1, //Searches for occurrences of the template image anywhere in the searchRect, assuming that the pattern is not rotated more than plus or minus 4 degrees.
+ IMAQ_MATCH_ROTATION_INVARIANT = 2, //Searches for occurrences of the pattern in the image with no restriction on the rotation of the pattern.
+ IMAQ_MATCHING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} MatchingMode;
+
+typedef enum MappingMethod_enum {
+ IMAQ_FULL_DYNAMIC = 0, //(Obsolete) When the image bit depth is 0, the function maps the full dynamic range of the 16-bit image to an 8-bit scale.
+ IMAQ_DOWNSHIFT = 1, //(Obsolete) When the image bit depth is 0, the function shifts the 16-bit image pixels to the right the number of times specified by the shiftCount element of the DisplayMapping structure.
+ IMAQ_RANGE = 2, //(Obsolete) When the image bit depth is 0, the function maps the pixel values in the range specified by the minimumValue and maximumValue elements of the DisplayMapping structure to an 8-bit scale.
+ IMAQ_90_PCT_DYNAMIC = 3, //(Obsolete) When the image bit depth to 0, the function maps the dynamic range containing the middle 90 percent of the cumulated histogram of the image to an 8-bit (256 grayscale values) scale.
+ IMAQ_PERCENT_RANGE = 4, //(Obsolete) When the image bit depth is 0, the function maps the pixel values in the relative percentage range (0 to 100) of the cumulated histogram specified by minimumValue and maximumValue to an 8-bit scale.
+ IMAQ_DEFAULT_MAPPING = 10, //If the bit depth is 0, the function maps the 16-bit image to 8 bits by following the IMAQ_FULL_DYNAMIC_ALWAYS behavior; otherwise, the function shifts the image data to the right according to the IMAQ_MOST_SIGNIFICANT behavior.
+ IMAQ_MOST_SIGNIFICANT = 11, //The function shifts the 16-bit image pixels to the right until the 8 most significant bits of the image data are remaining.
+ IMAQ_FULL_DYNAMIC_ALWAYS = 12, //The function maps the full dynamic range of the 16-bit image to an 8-bit scale.
+ IMAQ_DOWNSHIFT_ALWAYS = 13, //The function shifts the 16-bit image pixels to the right the number of times specified by the shiftCount element of the DisplayMapping structure.
+ IMAQ_RANGE_ALWAYS = 14, //The function maps the pixel values in the range specified by the minimumValue and maximumValue elements of the DisplayMapping structure to an 8-bit scale.
+ IMAQ_90_PCT_DYNAMIC_ALWAYS = 15, //The function maps the dynamic range containing the middle 90 percent of the cumulated histogram of the image to an 8-bit (256 grayscale values) scale.
+ IMAQ_PERCENT_RANGE_ALWAYS = 16, //The function maps the pixel values in the relative percentage range (0 to 100) of the cumulated histogram specified by minimumValue and maximumValue to an 8-bit scale.
+ IMAQ_MAPPING_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} MappingMethod;
+
+typedef enum ComparisonFunction_enum {
+ IMAQ_CLEAR_LESS = 0, //The comparison is true if the source pixel value is less than the comparison image pixel value.
+ IMAQ_CLEAR_LESS_OR_EQUAL = 1, //The comparison is true if the source pixel value is less than or equal to the comparison image pixel value.
+ IMAQ_CLEAR_EQUAL = 2, //The comparison is true if the source pixel value is equal to the comparison image pixel value.
+ IMAQ_CLEAR_GREATER_OR_EQUAL = 3, //The comparison is true if the source pixel value is greater than or equal to the comparison image pixel value.
+ IMAQ_CLEAR_GREATER = 4, //The comparison is true if the source pixel value is greater than the comparison image pixel value.
+ IMAQ_COMPARE_FUNCTION_SIZE_GUARD = 0xFFFFFFFF
+} ComparisonFunction;
+
+typedef enum LineGaugeMethod_enum {
+ IMAQ_EDGE_TO_EDGE = 0, //Measures from the first edge on the line to the last edge on the line.
+ IMAQ_EDGE_TO_POINT = 1, //Measures from the first edge on the line to the end point of the line.
+ IMAQ_POINT_TO_EDGE = 2, //Measures from the start point of the line to the first edge on the line.
+ IMAQ_POINT_TO_POINT = 3, //Measures from the start point of the line to the end point of the line.
+ IMAQ_LINE_GAUGE_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} LineGaugeMethod;
+
+typedef enum Direction3D_enum {
+ IMAQ_3D_NW = 0, //The viewing angle for the 3D image is from the northwest.
+ IMAQ_3D_SW = 1, //The viewing angle for the 3D image is from the southwest.
+ IMAQ_3D_SE = 2, //The viewing angle for the 3D image is from the southeast.
+ IMAQ_3D_NE = 3, //The viewing angle for the 3D image is from the northeast.
+ IMAQ_DIRECTION_3D_SIZE_GUARD = 0xFFFFFFFF
+} Direction3D;
+
+typedef enum LearningMode_enum {
+ IMAQ_LEARN_ALL = 0, //The function extracts information for shift- and rotation-invariant matching.
+ IMAQ_LEARN_SHIFT_INFORMATION = 1, //The function extracts information for shift-invariant matching.
+ IMAQ_LEARN_ROTATION_INFORMATION = 2, //The function extracts information for rotation-invariant matching.
+ IMAQ_LEARNING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} LearningMode;
+
+typedef enum KernelFamily_enum {
+ IMAQ_GRADIENT_FAMILY = 0, //The kernel is in the gradient family.
+ IMAQ_LAPLACIAN_FAMILY = 1, //The kernel is in the Laplacian family.
+ IMAQ_SMOOTHING_FAMILY = 2, //The kernel is in the smoothing family.
+ IMAQ_GAUSSIAN_FAMILY = 3, //The kernel is in the Gaussian family.
+ IMAQ_KERNEL_FAMILY_SIZE_GUARD = 0xFFFFFFFF
+} KernelFamily;
+
+typedef enum InterpolationMethod_enum {
+ IMAQ_ZERO_ORDER = 0, //The function uses an interpolation method that interpolates new pixel values using the nearest valid neighboring pixel.
+ IMAQ_BILINEAR = 1, //The function uses an interpolation method that interpolates new pixel values using a bidirectional average of the neighboring pixels.
+ IMAQ_QUADRATIC = 2, //The function uses an interpolation method that interpolates new pixel values using a quadratic approximating polynomial.
+ IMAQ_CUBIC_SPLINE = 3, //The function uses an interpolation method that interpolates new pixel values by fitting them to a cubic spline curve, where the curve is based on known pixel values from the image.
+ IMAQ_BILINEAR_FIXED = 4, //The function uses an interpolation method that interpolates new pixel values using a bidirectional average of the neighboring pixels.
+ IMAQ_INTERPOLATION_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} InterpolationMethod;
+
+typedef enum ImageType_enum {
+ IMAQ_IMAGE_U8 = 0, //The image type is 8-bit unsigned integer grayscale.
+ IMAQ_IMAGE_U16 = 7, //The image type is 16-bit unsigned integer grayscale.
+ IMAQ_IMAGE_I16 = 1, //The image type is 16-bit signed integer grayscale.
+ IMAQ_IMAGE_SGL = 2, //The image type is 32-bit floating-point grayscale.
+ IMAQ_IMAGE_COMPLEX = 3, //The image type is complex.
+ IMAQ_IMAGE_RGB = 4, //The image type is RGB color.
+ IMAQ_IMAGE_HSL = 5, //The image type is HSL color.
+ IMAQ_IMAGE_RGB_U64 = 6, //The image type is 64-bit unsigned RGB color.
+ IMAQ_IMAGE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ImageType;
+
+typedef enum ImageFeatureMode_enum {
+ IMAQ_COLOR_AND_SHAPE_FEATURES = 0, //Instructs the function to use the color and the shape features of the color pattern.
+ IMAQ_COLOR_FEATURES = 1, //Instructs the function to use the color features of the color pattern.
+ IMAQ_SHAPE_FEATURES = 2, //Instructs the function to use the shape features of the color pattern.
+ IMAQ_FEATURE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ImageFeatureMode;
+
+typedef enum FontColor_enum {
+ IMAQ_WHITE = 0, //Draws text in white.
+ IMAQ_BLACK = 1, //Draws text in black.
+ IMAQ_INVERT = 2, //Inverts the text pixels.
+ IMAQ_BLACK_ON_WHITE = 3, //Draws text in black with a white background.
+ IMAQ_WHITE_ON_BLACK = 4, //Draws text in white with a black background.
+ IMAQ_FONT_COLOR_SIZE_GUARD = 0xFFFFFFFF
+} FontColor;
+
+typedef enum FlipAxis_enum {
+ IMAQ_HORIZONTAL_AXIS = 0, //Flips the image over the central horizontal axis.
+ IMAQ_VERTICAL_AXIS = 1, //Flips the image over the central vertical axis.
+ IMAQ_CENTER_AXIS = 2, //Flips the image over both the central vertical and horizontal axes.
+ IMAQ_DIAG_L_TO_R_AXIS = 3, //Flips the image over an axis from the upper left corner to lower right corner.
+ IMAQ_DIAG_R_TO_L_AXIS = 4, //Flips the image over an axis from the upper right corner to lower left corner.
+ IMAQ_FLIP_AXIS_SIZE_GUARD = 0xFFFFFFFF
+} FlipAxis;
+
+typedef enum EdgeProcess_enum {
+ IMAQ_FIRST = 0, //The function looks for the first edge.
+ IMAQ_FIRST_AND_LAST = 1, //The function looks for the first and last edge.
+ IMAQ_ALL = 2, //The function looks for all edges.
+ IMAQ_BEST = 3, //The function looks for the best edge.
+ IMAQ_EDGE_PROCESS_SIZE_GUARD = 0xFFFFFFFF
+} EdgeProcess;
+
+typedef enum DrawMode_enum {
+ IMAQ_DRAW_VALUE = 0, //Draws the boundary of the object with the specified pixel value.
+ IMAQ_DRAW_INVERT = 2, //Inverts the pixel values of the boundary of the object.
+ IMAQ_PAINT_VALUE = 1, //Fills the object with the given pixel value.
+ IMAQ_PAINT_INVERT = 3, //Inverts the pixel values of the object.
+ IMAQ_HIGHLIGHT_VALUE = 4, //The function fills the object by highlighting the enclosed pixels with the color of the object.
+ IMAQ_DRAW_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DrawMode;
+
+typedef enum NearestNeighborMetric_enum {
+ IMAQ_METRIC_MAXIMUM = 0, //The maximum metric.
+ IMAQ_METRIC_SUM = 1, //The sum metric.
+ IMAQ_METRIC_EUCLIDEAN = 2, //The Euclidean metric.
+ IMAQ_NEAREST_NEIGHBOR_METRIC_SIZE_GUARD = 0xFFFFFFFF
+} NearestNeighborMetric;
+
+typedef enum ReadResolution_enum {
+ IMAQ_LOW_RESOLUTION = 0, //Configures NI Vision to use low resolution during the read process.
+ IMAQ_MEDIUM_RESOLUTION = 1, //Configures NI Vision to use medium resolution during the read process.
+ IMAQ_HIGH_RESOLUTION = 2, //Configures NI Vision to use high resolution during the read process.
+ IMAQ_READ_RESOLUTION_SIZE_GUARD = 0xFFFFFFFF
+} ReadResolution;
+
+typedef enum ThresholdMode_enum {
+ IMAQ_FIXED_RANGE = 0, //Performs thresholding using the values you provide in the lowThreshold and highThreshold elements of OCRProcessingOptions.
+ IMAQ_COMPUTED_UNIFORM = 1, //Calculates a single threshold value for the entire ROI.
+ IMAQ_COMPUTED_LINEAR = 2, //Calculates a value on the left side of the ROI, calculates a value on the right side of the ROI, and linearly fills the middle values from left to right.
+ IMAQ_COMPUTED_NONLINEAR = 3, //Divides the ROI into the number of blocks specified by the blockCount element of OCRProcessingOptions and calculates a threshold value for each block.
+ IMAQ_THRESHOLD_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ThresholdMode;
+
+typedef enum ReadStrategy_enum {
+ IMAQ_READ_AGGRESSIVE = 0, //Configures NI Vision to perform fewer checks when analyzing objects to determine if they match trained characters.
+ IMAQ_READ_CONSERVATIVE = 1, //Configures NI Vision to perform more checks to determine if an object matches a trained character.
+ IMAQ_READ_STRATEGY_SIZE_GUARD = 0xFFFFFFFF
+} ReadStrategy;
+
+typedef enum MeasurementType_enum {
+ IMAQ_MT_CENTER_OF_MASS_X = 0, //X-coordinate of the point representing the average position of the total particle mass, assuming every point in the particle has a constant density.
+ IMAQ_MT_CENTER_OF_MASS_Y = 1, //Y-coordinate of the point representing the average position of the total particle mass, assuming every point in the particle has a constant density.
+ IMAQ_MT_FIRST_PIXEL_X = 2, //X-coordinate of the highest, leftmost particle pixel.
+ IMAQ_MT_FIRST_PIXEL_Y = 3, //Y-coordinate of the highest, leftmost particle pixel.
+ IMAQ_MT_BOUNDING_RECT_LEFT = 4, //X-coordinate of the leftmost particle point.
+ IMAQ_MT_BOUNDING_RECT_TOP = 5, //Y-coordinate of highest particle point.
+ IMAQ_MT_BOUNDING_RECT_RIGHT = 6, //X-coordinate of the rightmost particle point.
+ IMAQ_MT_BOUNDING_RECT_BOTTOM = 7, //Y-coordinate of the lowest particle point.
+ IMAQ_MT_MAX_FERET_DIAMETER_START_X = 8, //X-coordinate of the start of the line segment connecting the two perimeter points that are the furthest apart.
+ IMAQ_MT_MAX_FERET_DIAMETER_START_Y = 9, //Y-coordinate of the start of the line segment connecting the two perimeter points that are the furthest apart.
+ IMAQ_MT_MAX_FERET_DIAMETER_END_X = 10, //X-coordinate of the end of the line segment connecting the two perimeter points that are the furthest apart.
+ IMAQ_MT_MAX_FERET_DIAMETER_END_Y = 11, //Y-coordinate of the end of the line segment connecting the two perimeter points that are the furthest apart.
+ IMAQ_MT_MAX_HORIZ_SEGMENT_LENGTH_LEFT = 12, //X-coordinate of the leftmost pixel in the longest row of contiguous pixels in the particle.
+ IMAQ_MT_MAX_HORIZ_SEGMENT_LENGTH_RIGHT = 13, //X-coordinate of the rightmost pixel in the longest row of contiguous pixels in the particle.
+ IMAQ_MT_MAX_HORIZ_SEGMENT_LENGTH_ROW = 14, //Y-coordinate of all of the pixels in the longest row of contiguous pixels in the particle.
+ IMAQ_MT_BOUNDING_RECT_WIDTH = 16, //Distance between the x-coordinate of the leftmost particle point and the x-coordinate of the rightmost particle point.
+ IMAQ_MT_BOUNDING_RECT_HEIGHT = 17, //Distance between the y-coordinate of highest particle point and the y-coordinate of the lowest particle point.
+ IMAQ_MT_BOUNDING_RECT_DIAGONAL = 18, //Distance between opposite corners of the bounding rectangle.
+ IMAQ_MT_PERIMETER = 19, //Length of the outer boundary of the particle.
+ IMAQ_MT_CONVEX_HULL_PERIMETER = 20, //Perimeter of the smallest convex polygon containing all points in the particle.
+ IMAQ_MT_HOLES_PERIMETER = 21, //Sum of the perimeters of each hole in the particle.
+ IMAQ_MT_MAX_FERET_DIAMETER = 22, //Distance between the start and end of the line segment connecting the two perimeter points that are the furthest apart.
+ IMAQ_MT_EQUIVALENT_ELLIPSE_MAJOR_AXIS = 23, //Length of the major axis of the ellipse with the same perimeter and area as the particle.
+ IMAQ_MT_EQUIVALENT_ELLIPSE_MINOR_AXIS = 24, //Length of the minor axis of the ellipse with the same perimeter and area as the particle.
+ IMAQ_MT_EQUIVALENT_ELLIPSE_MINOR_AXIS_FERET = 25, //Length of the minor axis of the ellipse with the same area as the particle, and Major Axis equal in length to the Max Feret Diameter.
+ IMAQ_MT_EQUIVALENT_RECT_LONG_SIDE = 26, //Longest side of the rectangle with the same perimeter and area as the particle.
+ IMAQ_MT_EQUIVALENT_RECT_SHORT_SIDE = 27, //Shortest side of the rectangle with the same perimeter and area as the particle.
+ IMAQ_MT_EQUIVALENT_RECT_DIAGONAL = 28, //Distance between opposite corners of the rectangle with the same perimeter and area as the particle.
+ IMAQ_MT_EQUIVALENT_RECT_SHORT_SIDE_FERET = 29, //Shortest side of the rectangle with the same area as the particle, and longest side equal in length to the Max Feret Diameter.
+ IMAQ_MT_AVERAGE_HORIZ_SEGMENT_LENGTH = 30, //Average length of a horizontal segment in the particle.
+ IMAQ_MT_AVERAGE_VERT_SEGMENT_LENGTH = 31, //Average length of a vertical segment in the particle.
+ IMAQ_MT_HYDRAULIC_RADIUS = 32, //The particle area divided by the particle perimeter.
+ IMAQ_MT_WADDEL_DISK_DIAMETER = 33, //Diameter of a disk with the same area as the particle.
+ IMAQ_MT_AREA = 35, //Area of the particle.
+ IMAQ_MT_HOLES_AREA = 36, //Sum of the areas of each hole in the particle.
+ IMAQ_MT_PARTICLE_AND_HOLES_AREA = 37, //Area of a particle that completely covers the image.
+ IMAQ_MT_CONVEX_HULL_AREA = 38, //Area of the smallest convex polygon containing all points in the particle.
+ IMAQ_MT_IMAGE_AREA = 39, //Area of the image.
+ IMAQ_MT_NUMBER_OF_HOLES = 41, //Number of holes in the particle.
+ IMAQ_MT_NUMBER_OF_HORIZ_SEGMENTS = 42, //Number of horizontal segments in the particle.
+ IMAQ_MT_NUMBER_OF_VERT_SEGMENTS = 43, //Number of vertical segments in the particle.
+ IMAQ_MT_ORIENTATION = 45, //The angle of the line that passes through the particle Center of Mass about which the particle has the lowest moment of inertia.
+ IMAQ_MT_MAX_FERET_DIAMETER_ORIENTATION = 46, //The angle of the line segment connecting the two perimeter points that are the furthest apart.
+ IMAQ_MT_AREA_BY_IMAGE_AREA = 48, //Percentage of the particle Area covering the Image Area.
+ IMAQ_MT_AREA_BY_PARTICLE_AND_HOLES_AREA = 49, //Percentage of the particle Area in relation to its Particle and Holes Area.
+ IMAQ_MT_RATIO_OF_EQUIVALENT_ELLIPSE_AXES = 50, //Equivalent Ellipse Major Axis divided by Equivalent Ellipse Minor Axis.
+ IMAQ_MT_RATIO_OF_EQUIVALENT_RECT_SIDES = 51, //Equivalent Rect Long Side divided by Equivalent Rect Short Side.
+ IMAQ_MT_ELONGATION_FACTOR = 53, //Max Feret Diameter divided by Equivalent Rect Short Side (Feret).
+ IMAQ_MT_COMPACTNESS_FACTOR = 54, //Area divided by the product of Bounding Rect Width and Bounding Rect Height.
+ IMAQ_MT_HEYWOOD_CIRCULARITY_FACTOR = 55, //Perimeter divided by the circumference of a circle with the same area.
+ IMAQ_MT_TYPE_FACTOR = 56, //Factor relating area to moment of inertia.
+ IMAQ_MT_SUM_X = 58, //The sum of all x-coordinates in the particle.
+ IMAQ_MT_SUM_Y = 59, //The sum of all y-coordinates in the particle.
+ IMAQ_MT_SUM_XX = 60, //The sum of all x-coordinates squared in the particle.
+ IMAQ_MT_SUM_XY = 61, //The sum of all x-coordinates times y-coordinates in the particle.
+ IMAQ_MT_SUM_YY = 62, //The sum of all y-coordinates squared in the particle.
+ IMAQ_MT_SUM_XXX = 63, //The sum of all x-coordinates cubed in the particle.
+ IMAQ_MT_SUM_XXY = 64, //The sum of all x-coordinates squared times y-coordinates in the particle.
+ IMAQ_MT_SUM_XYY = 65, //The sum of all x-coordinates times y-coordinates squared in the particle.
+ IMAQ_MT_SUM_YYY = 66, //The sum of all y-coordinates cubed in the particle.
+ IMAQ_MT_MOMENT_OF_INERTIA_XX = 68, //The moment of inertia in the x-direction twice.
+ IMAQ_MT_MOMENT_OF_INERTIA_XY = 69, //The moment of inertia in the x and y directions.
+ IMAQ_MT_MOMENT_OF_INERTIA_YY = 70, //The moment of inertia in the y-direction twice.
+ IMAQ_MT_MOMENT_OF_INERTIA_XXX = 71, //The moment of inertia in the x-direction three times.
+ IMAQ_MT_MOMENT_OF_INERTIA_XXY = 72, //The moment of inertia in the x-direction twice and the y-direction once.
+ IMAQ_MT_MOMENT_OF_INERTIA_XYY = 73, //The moment of inertia in the x-direction once and the y-direction twice.
+ IMAQ_MT_MOMENT_OF_INERTIA_YYY = 74, //The moment of inertia in the y-direction three times.
+ IMAQ_MT_NORM_MOMENT_OF_INERTIA_XX = 75, //The normalized moment of inertia in the x-direction twice.
+ IMAQ_MT_NORM_MOMENT_OF_INERTIA_XY = 76, //The normalized moment of inertia in the x- and y-directions.
+ IMAQ_MT_NORM_MOMENT_OF_INERTIA_YY = 77, //The normalized moment of inertia in the y-direction twice.
+ IMAQ_MT_NORM_MOMENT_OF_INERTIA_XXX = 78, //The normalized moment of inertia in the x-direction three times.
+ IMAQ_MT_NORM_MOMENT_OF_INERTIA_XXY = 79, //The normalized moment of inertia in the x-direction twice and the y-direction once.
+ IMAQ_MT_NORM_MOMENT_OF_INERTIA_XYY = 80, //The normalized moment of inertia in the x-direction once and the y-direction twice.
+ IMAQ_MT_NORM_MOMENT_OF_INERTIA_YYY = 81, //The normalized moment of inertia in the y-direction three times.
+ IMAQ_MT_HU_MOMENT_1 = 82, //The first Hu moment.
+ IMAQ_MT_HU_MOMENT_2 = 83, //The second Hu moment.
+ IMAQ_MT_HU_MOMENT_3 = 84, //The third Hu moment.
+ IMAQ_MT_HU_MOMENT_4 = 85, //The fourth Hu moment.
+ IMAQ_MT_HU_MOMENT_5 = 86, //The fifth Hu moment.
+ IMAQ_MT_HU_MOMENT_6 = 87, //The sixth Hu moment.
+ IMAQ_MT_HU_MOMENT_7 = 88, //The seventh Hu moment.
+ IMAQ_MEASUREMENT_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} MeasurementType;
+
+typedef enum GeometricMatchingMode_enum {
+ IMAQ_GEOMETRIC_MATCH_SHIFT_INVARIANT = 0, //Searches for occurrences of the pattern in the image, assuming that the pattern is not rotated more than plus or minus 5 degrees.
+ IMAQ_GEOMETRIC_MATCH_ROTATION_INVARIANT = 1, //Searches for occurrences of the pattern in the image with reduced restriction on the rotation of the pattern.
+ IMAQ_GEOMETRIC_MATCH_SCALE_INVARIANT = 2, //Searches for occurrences of the pattern in the image with reduced restriction on the size of the pattern.
+ IMAQ_GEOMETRIC_MATCH_OCCLUSION_INVARIANT = 4, //Searches for occurrences of the pattern in the image, allowing for a specified percentage of the pattern to be occluded.
+ IMAQ_GEOMETRIC_MATCHING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} GeometricMatchingMode;
+
+typedef enum ButtonLabel_enum {
+ IMAQ_BUTTON_OK = 0, //The label "OK".
+ IMAQ_BUTTON_SAVE = 1, //The label "Save".
+ IMAQ_BUTTON_SELECT = 2, //The label "Select".
+ IMAQ_BUTTON_LOAD = 3, //The label "Load".
+ IMAQ_BUTTON_LABEL_SIZE_GUARD = 0xFFFFFFFF
+} ButtonLabel;
+
+typedef enum NearestNeighborMethod_enum {
+ IMAQ_MINIMUM_MEAN_DISTANCE = 0, //The minimum mean distance method.
+ IMAQ_K_NEAREST_NEIGHBOR = 1, //The k-nearest neighbor method.
+ IMAQ_NEAREST_PROTOTYPE = 2, //The nearest prototype method.
+ IMAQ_NEAREST_NEIGHBOR_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} NearestNeighborMethod;
+
+typedef enum QRMirrorMode_enum {
+ IMAQ_QR_MIRROR_MODE_AUTO_DETECT = -2, //The function should determine if the QR code is mirrored.
+ IMAQ_QR_MIRROR_MODE_MIRRORED = 1, //The function should expect the QR code to appear mirrored.
+ IMAQ_QR_MIRROR_MODE_NORMAL = 0, //The function should expect the QR code to appear normal.
+ IMAQ_QR_MIRROR_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRMirrorMode;
+
+typedef enum ColumnProcessingMode_enum {
+ IMAQ_AVERAGE_COLUMNS = 0, //Averages the data extracted for edge detection.
+ IMAQ_MEDIAN_COLUMNS = 1, //Takes the median of the data extracted for edge detection.
+ IMAQ_COLUMN_PROCESSING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ColumnProcessingMode;
+
+typedef enum FindReferenceDirection_enum {
+ IMAQ_LEFT_TO_RIGHT_DIRECT = 0, //Searches from the left side of the search area to the right side of the search area for a direct axis.
+ IMAQ_LEFT_TO_RIGHT_INDIRECT = 1, //Searches from the left side of the search area to the right side of the search area for an indirect axis.
+ IMAQ_TOP_TO_BOTTOM_DIRECT = 2, //Searches from the top of the search area to the bottom of the search area for a direct axis.
+ IMAQ_TOP_TO_BOTTOM_INDIRECT = 3, //Searches from the top of the search area to the bottom of the search area for an indirect axis.
+ IMAQ_RIGHT_TO_LEFT_DIRECT = 4, //Searches from the right side of the search area to the left side of the search area for a direct axis.
+ IMAQ_RIGHT_TO_LEFT_INDIRECT = 5, //Searches from the right side of the search area to the left side of the search area for an indirect axis.
+ IMAQ_BOTTOM_TO_TOP_DIRECT = 6, //Searches from the bottom of the search area to the top of the search area for a direct axis.
+ IMAQ_BOTTOM_TO_TOP_INDIRECT = 7, //Searches from the bottom of the search area to the top of the search area for an indirect axis.
+ IMAQ_FIND_COORD_SYS_DIR_SIZE_GUARD = 0xFFFFFFFF
+} FindReferenceDirection;
+
+typedef enum MulticoreOperation_enum {
+ IMAQ_GET_CORES = 0, //The number of processor cores NI Vision is currently using.
+ IMAQ_SET_CORES = 1, //The number of processor cores for NI Vision to use.
+ IMAQ_USE_MAX_AVAILABLE = 2, //Use the maximum number of available processor cores.
+ IMAQ_MULTICORE_OPERATION_SIZE_GUARD = 0xFFFFFFFF
+} MulticoreOperation;
+
+typedef enum GroupBehavior_enum {
+ IMAQ_GROUP_CLEAR = 0, //Sets the behavior of the overlay group to clear the current settings when an image is transformed.
+ IMAQ_GROUP_KEEP = 1, //Sets the behavior of the overlay group to keep the current settings when an image is transformed.
+ IMAQ_GROUP_TRANSFORM = 2, //Sets the behavior of the overlay group to transform with the image.
+ IMAQ_GROUP_BEHAVIOR_SIZE_GUARD = 0xFFFFFFFF
+} GroupBehavior;
+
+typedef enum QRDimensions_enum {
+ IMAQ_QR_DIMENSIONS_AUTO_DETECT = 0, //The function will automatically determine the dimensions of the QR code.
+ IMAQ_QR_DIMENSIONS_11x11 = 11, //Specifies the dimensions of the QR code as 11 x 11.
+ IMAQ_QR_DIMENSIONS_13x13 = 13, //Specifies the dimensions of the QR code as 13 x 13.
+ IMAQ_QR_DIMENSIONS_15x15 = 15, //Specifies the dimensions of the QR code as 15 x 15.
+ IMAQ_QR_DIMENSIONS_17x17 = 17, //Specifies the dimensions of the QR code as 17 x 17.
+ IMAQ_QR_DIMENSIONS_21x21 = 21, //Specifies the dimensions of the QR code as 21 x 21.
+ IMAQ_QR_DIMENSIONS_25x25 = 25, //Specifies the dimensions of the QR code as 25 x 25.
+ IMAQ_QR_DIMENSIONS_29x29 = 29, //Specifies the dimensions of the QR code as 29 x 29.
+ IMAQ_QR_DIMENSIONS_33x33 = 33, //Specifies the dimensions of the QR code as 33 x 33.
+ IMAQ_QR_DIMENSIONS_37x37 = 37, //Specifies the dimensions of the QR code as 37 x 37.
+ IMAQ_QR_DIMENSIONS_41x41 = 41, //Specifies the dimensions of the QR code as 41 x 41.
+ IMAQ_QR_DIMENSIONS_45x45 = 45, //Specifies the dimensions of the QR code as 45 x 45.
+ IMAQ_QR_DIMENSIONS_49x49 = 49, //Specifies the dimensions of the QR code as 49 x 49.
+ IMAQ_QR_DIMENSIONS_53x53 = 53, //Specifies the dimensions of the QR code as 53 x 53.
+ IMAQ_QR_DIMENSIONS_57x57 = 57, //Specifies the dimensions of the QR code as 57 x 57.
+ IMAQ_QR_DIMENSIONS_61x61 = 61, //Specifies the dimensions of the QR code as 61 x 61.
+ IMAQ_QR_DIMENSIONS_65x65 = 65, //Specifies the dimensions of the QR code as 65 x 65.
+ IMAQ_QR_DIMENSIONS_69x69 = 69, //Specifies the dimensions of the QR code as 69 x 69.
+ IMAQ_QR_DIMENSIONS_73x73 = 73, //Specifies the dimensions of the QR code as 73 x 73.
+ IMAQ_QR_DIMENSIONS_77x77 = 77, //Specifies the dimensions of the QR code as 77 x 77.
+ IMAQ_QR_DIMENSIONS_81x81 = 81, //Specifies the dimensions of the QR code as 81 x 81.
+ IMAQ_QR_DIMENSIONS_85x85 = 85, //Specifies the dimensions of the QR code as 85 x 85.
+ IMAQ_QR_DIMENSIONS_89x89 = 89, //Specifies the dimensions of the QR code as 89 x 89.
+ IMAQ_QR_DIMENSIONS_93x93 = 93, //Specifies the dimensions of the QR code as 93 x 93.
+ IMAQ_QR_DIMENSIONS_97x97 = 97, //Specifies the dimensions of the QR code as 97 x 97.
+ IMAQ_QR_DIMENSIONS_101x101 = 101, //Specifies the dimensions of the QR code as 101 x 101.
+ IMAQ_QR_DIMENSIONS_105x105 = 105, //Specifies the dimensions of the QR code as 105 x 105.
+ IMAQ_QR_DIMENSIONS_109x109 = 109, //Specifies the dimensions of the QR code as 109 x 109.
+ IMAQ_QR_DIMENSIONS_113x113 = 113, //Specifies the dimensions of the QR code as 113 x 113.
+ IMAQ_QR_DIMENSIONS_117x117 = 117, //Specifies the dimensions of the QR code as 117 x 117.
+ IMAQ_QR_DIMENSIONS_121x121 = 121, //Specifies the dimensions of the QR code as 121 x 121.
+ IMAQ_QR_DIMENSIONS_125x125 = 125, //Specifies the dimensions of the QR code as 125 x 125.
+ IMAQ_QR_DIMENSIONS_129x129 = 129, //Specifies the dimensions of the QR code as 129 x 129.
+ IMAQ_QR_DIMENSIONS_133x133 = 133, //Specifies the dimensions of the QR code as 133 x 133.
+ IMAQ_QR_DIMENSIONS_137x137 = 137, //Specifies the dimensions of the QR code as 137 x 137.
+ IMAQ_QR_DIMENSIONS_141x141 = 141, //Specifies the dimensions of the QR code as 141 x 141.
+ IMAQ_QR_DIMENSIONS_145x145 = 145, //Specifies the dimensions of the QR code as 145 x 145.
+ IMAQ_QR_DIMENSIONS_149x149 = 149, //Specifies the dimensions of the QR code as 149 x 149.
+ IMAQ_QR_DIMENSIONS_153x153 = 153, //Specifies the dimensions of the QR code as 153 x 153.
+ IMAQ_QR_DIMENSIONS_157x157 = 157, //Specifies the dimensions of the QR code as 157 x 1537.
+ IMAQ_QR_DIMENSIONS_161x161 = 161, //Specifies the dimensions of the QR code as 161 x 161.
+ IMAQ_QR_DIMENSIONS_165x165 = 165, //Specifies the dimensions of the QR code as 165 x 165.
+ IMAQ_QR_DIMENSIONS_169x169 = 169, //Specifies the dimensions of the QR code as 169 x 169.
+ IMAQ_QR_DIMENSIONS_173x173 = 173, //Specifies the dimensions of the QR code as 173 x 173.
+ IMAQ_QR_DIMENSIONS_177x177 = 177, //Specifies the dimensions of the QR code as 177 x 177.
+ IMAQ_QR_DIMENSIONS_SIZE_GUARD = 0xFFFFFFFF
+} QRDimensions;
+
+typedef enum QRCellFilterMode_enum {
+ IMAQ_QR_CELL_FILTER_MODE_AUTO_DETECT = -2, //The function will try all filter modes and uses the one that decodes the QR code within the fewest iterations and utilizing the least amount of error correction.
+ IMAQ_QR_CELL_FILTER_MODE_AVERAGE = 0, //The function sets the pixel value for the cell to the average of the sampled pixels.
+ IMAQ_QR_CELL_FILTER_MODE_MEDIAN = 1, //The function sets the pixel value for the cell to the median of the sampled pixels.
+ IMAQ_QR_CELL_FILTER_MODE_CENTRAL_AVERAGE = 2, //The function sets the pixel value for the cell to the average of the pixels in the center of the cell sample.
+ IMAQ_QR_CELL_FILTER_MODE_HIGH_AVERAGE = 3, //The function sets the pixel value for the cell to the average value of the half of the sampled pixels with the highest pixel values.
+ IMAQ_QR_CELL_FILTER_MODE_LOW_AVERAGE = 4, //The function sets the pixel value for the cell to the average value of the half of the sampled pixels with the lowest pixel values.
+ IMAQ_QR_CELL_FILTER_MODE_VERY_HIGH_AVERAGE = 5, //The function sets the pixel value for the cell to the average value of the ninth of the sampled pixels with the highest pixel values.
+ IMAQ_QR_CELL_FILTER_MODE_VERY_LOW_AVERAGE = 6, //The function sets the pixel value for the cell to the average value of the ninth of the sampled pixels with the lowest pixel values.
+ IMAQ_QR_CELL_FILTER_MODE_ALL = 8, //The function tries each filter mode, starting with IMAQ_QR_CELL_FILTER_MODE_AVERAGE and ending with IMAQ_QR_CELL_FILTER_MODE_VERY_LOW_AVERAGE, stopping once a filter mode decodes correctly.
+ IMAQ_QR_CELL_FILTER_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRCellFilterMode;
+
+typedef enum RoundingMode_enum {
+ IMAQ_ROUNDING_MODE_OPTIMIZE = 0, //Rounds the result of a division using the best available method.
+ IMAQ_ROUNDING_MODE_TRUNCATE = 1, //Truncates the result of a division.
+ IMAQ_ROUNDING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} RoundingMode;
+
+typedef enum QRDemodulationMode_enum {
+ IMAQ_QR_DEMODULATION_MODE_AUTO_DETECT = -2, //The function will try each demodulation mode and use the one which decodes the QR code within the fewest iterations and utilizing the least amount of error correction.
+ IMAQ_QR_DEMODULATION_MODE_HISTOGRAM = 0, //The function uses a histogram of all of the QR cells to calculate a threshold.
+ IMAQ_QR_DEMODULATION_MODE_LOCAL_CONTRAST = 1, //The function examines each of the cell's neighbors to determine if the cell is on or off.
+ IMAQ_QR_DEMODULATION_MODE_COMBINED = 2, //The function uses the histogram of the QR code to calculate a threshold.
+ IMAQ_QR_DEMODULATION_MODE_ALL = 3, //The function tries IMAQ_QR_DEMODULATION_MODE_HISTOGRAM, then IMAQ_QR_DEMODULATION_MODE_LOCAL_CONTRAST and then IMAQ_QR_DEMODULATION_MODE_COMBINED, stopping once one mode is successful.
+ IMAQ_QR_DEMODULATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRDemodulationMode;
+
+typedef enum ContrastMode_enum {
+ IMAQ_ORIGINAL_CONTRAST = 0, //Instructs the geometric matching algorithm to find matches with the same contrast as the template.
+ IMAQ_REVERSED_CONTRAST = 1, //Instructs the geometric matching algorithm to find matches with the inverted contrast of the template.
+ IMAQ_BOTH_CONTRASTS = 2, //Instructs the geometric matching algorithm to find matches with the same and inverted contrast of the template.
+} ContrastMode;
+
+typedef enum QRPolarities_enum {
+ IMAQ_QR_POLARITY_AUTO_DETECT = -2, //The function should determine the polarity of the QR code.
+ IMAQ_QR_POLARITY_BLACK_ON_WHITE = 0, //The function should search for a QR code with dark data on a bright background.
+ IMAQ_QR_POLARITY_WHITE_ON_BLACK = 1, //The function should search for a QR code with bright data on a dark background.
+ IMAQ_QR_POLARITY_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRPolarities;
+
+typedef enum QRRotationMode_enum {
+ IMAQ_QR_ROTATION_MODE_UNLIMITED = 0, //The function allows for unlimited rotation.
+ IMAQ_QR_ROTATION_MODE_0_DEGREES = 1, //The function allows for ??? 5 degrees of rotation.
+ IMAQ_QR_ROTATION_MODE_90_DEGREES = 2, //The function allows for between 85 and 95 degrees of rotation.
+ IMAQ_QR_ROTATION_MODE_180_DEGREES = 3, //The function allows for between 175 and 185 degrees of rotation.
+ IMAQ_QR_ROTATION_MODE_270_DEGREES = 4, //The function allows for between 265 and 275 degrees of rotation.
+ IMAQ_QR_ROTATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRRotationMode;
+
+typedef enum QRGradingMode_enum {
+ IMAQ_QR_NO_GRADING = 0, //The function does not make any preparatory calculations.
+ IMAQ_QR_GRADING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRGradingMode;
+
+typedef enum StraightEdgeSearchMode_enum {
+ IMAQ_USE_FIRST_RAKE_EDGES = 0, //Fits a straight edge on the first points detected using a rake.
+ IMAQ_USE_BEST_RAKE_EDGES = 1, //Fits a straight edge on the best points detected using a rake.
+ IMAQ_USE_BEST_HOUGH_LINE = 2, //Finds the strongest straight edge using all points detected on a rake.
+ IMAQ_USE_FIRST_PROJECTION_EDGE = 3, //Uses the location of the first projected edge as the straight edge.
+ IMAQ_USE_BEST_PROJECTION_EDGE = 4, //Finds the strongest projected edge location to determine the straight edge.
+ IMAQ_STRAIGHT_EDGE_SEARCH_SIZE_GUARD = 0xFFFFFFFF
+} StraightEdgeSearchMode;
+
+typedef enum SearchDirection_enum {
+ IMAQ_SEARCH_DIRECTION_LEFT_TO_RIGHT = 0, //Searches from the left side of the search area to the right side of the search area.
+ IMAQ_SEARCH_DIRECTION_RIGHT_TO_LEFT = 1, //Searches from the right side of the search area to the left side of the search area.
+ IMAQ_SEARCH_DIRECTION_TOP_TO_BOTTOM = 2, //Searches from the top side of the search area to the bottom side of the search area.
+ IMAQ_SEARCH_DIRECTION_BOTTOM_TO_TOP = 3, //Searches from the bottom side of the search area to the top side of the search area.
+ IMAQ_SEARCH_DIRECTION_SIZE_GUARD = 0xFFFFFFFF
+} SearchDirection;
+
+typedef enum QRStreamMode_enum {
+ IMAQ_QR_MODE_NUMERIC = 0, //Specifies that the data was encoded using numeric mode.
+ IMAQ_QR_MODE_ALPHANUMERIC = 1, //Specifies that the data was encoded using alpha-numeric mode.
+ IMAQ_QR_MODE_RAW_BYTE = 2, //Specifies that the data was not encoded but is only raw binary bytes, or encoded in JIS-8.
+ IMAQ_QR_MODE_EAN128_TOKEN = 3, //Specifies that the data has a special meaning represented by the application ID.
+ IMAQ_QR_MODE_EAN128_DATA = 4, //Specifies that the data has a special meaning represented by the application ID.
+ IMAQ_QR_MODE_ECI = 5, //Specifies that the data was meant to be read using the language represented in the language ID.
+ IMAQ_QR_MODE_KANJI = 6, //Specifies that the data was encoded in Shift-JIS16 Japanese.
+ IMAQ_QR_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRStreamMode;
+
+typedef enum ParticleClassifierType_enum {
+ IMAQ_PARTICLE_LARGEST = 0, //Use only the largest particle in the image.
+ IMAQ_PARTICLE_ALL = 1, //Use all particles in the image.
+ IMAQ_PARTICLE_CLASSIFIER_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ParticleClassifierType;
+
+typedef enum QRCellSampleSize_enum {
+ IMAQ_QR_CELL_SAMPLE_SIZE_AUTO_DETECT = -2, //The function will try each sample size and use the one which decodes the QR code within the fewest iterations and utilizing the least amount of error correction.
+ IMAQ_QR_CELL_SAMPLE_SIZE1X1 = 1, //The function will use a 1x1 sized sample from each cell.
+ IMAQ_QR_CELL_SAMPLE_SIZE2X2 = 2, //The function will use a 2x2 sized sample from each cell.
+ IMAQ_QR_CELL_SAMPLE_SIZE3X3 = 3, //The function will use a 3x3 sized sample from each cell.
+ IMAQ_QR_CELL_SAMPLE_SIZE4X4 = 4, //The function will use a 4x4 sized sample from each cell.
+ IMAQ_QR_CELL_SAMPLE_SIZE5X5 = 5, //The function will use a 5x5 sized sample from each cell.
+ IMAQ_QR_CELL_SAMPLE_SIZE6X6 = 6, //The function will use a 6x6 sized sample from each cell.
+ IMAQ_QR_CELL_SAMPLE_SIZE7X7 = 7, //The function will use a 7x7 sized sample from each cell.
+ IMAQ_QR_CELL_SAMPLE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} QRCellSampleSize;
+
+typedef enum RakeProcessType_enum {
+ IMAQ_GET_FIRST_EDGES = 0,
+ IMAQ_GET_FIRST_AND_LAST_EDGES = 1,
+ IMAQ_GET_ALL_EDGES = 2,
+ IMAQ_GET_BEST_EDGES = 3,
+ IMAQ_RAKE_PROCESS_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} RakeProcessType;
+
+typedef enum GeometricSetupDataItem_enum {
+ IMAQ_CURVE_EXTRACTION_MODE = 0, //Specifies how the function identifies curves in the image.
+ IMAQ_CURVE_EDGE_THRSHOLD = 1, //Specifies the minimum contrast an edge pixel must have for it to be considered part of a curve.
+ IMAQ_CURVE_EDGE_FILTER = 2, //Specifies the width of the edge filter that the function uses to identify curves in the image.
+ IMAQ_MINIMUM_CURVE_LENGTH = 3, //Specifies the length, in pixels, of the smallest curve that you want the function to identify.
+ IMAQ_CURVE_ROW_SEARCH_STEP_SIZE = 4, //Specifies the distance, in the y direction, between the image rows that the algorithm inspects for curve seed points.
+ IMAQ_CURVE_COL_SEARCH_STEP_SIZE = 5, //Specifies the distance, in the x direction, between the image columns that the algorithm inspects for curve seed points.
+ IMAQ_CURVE_MAX_END_POINT_GAP = 6, //Specifies the maximum gap, in pixels, between the endpoints of a curve that the function identifies as a closed curve.
+ IMAQ_EXTRACT_CLOSED_CURVES = 7, //Specifies whether to identify only closed curves in the image.
+ IMAQ_ENABLE_SUBPIXEL_CURVE_EXTRACTION = 8, //The function ignores this option.
+ IMAQ_ENABLE_CORRELATION_SCORE = 9, //Specifies that the function should calculate the Correlation Score and return it for each match result.
+ IMAQ_ENABLE_SUBPIXEL_ACCURACY = 10, //Determines whether to return the match results with subpixel accuracy.
+ IMAQ_SUBPIXEL_ITERATIONS = 11, //Specifies the maximum number of incremental improvements used to refine matches using subpixel information.
+ IMAQ_SUBPIXEL_TOLERANCE = 12, //Specifies the maximum amount of change, in pixels, between consecutive incremental improvements in the match position before the function stops refining the match position.
+ IMAQ_INITIAL_MATCH_LIST_LENGTH = 13, //Specifies the maximum size of the match list.
+ IMAQ_ENABLE_TARGET_TEMPLATE_CURVESCORE = 14, //Specifies whether the function should calculate the match curve to template curve score and return it for each match result.
+ IMAQ_MINIMUM_MATCH_SEPARATION_DISTANCE = 15, //Specifies the minimum separation distance, in pixels, between the origins of two matches that have unique positions.
+ IMAQ_MINIMUM_MATCH_SEPARATION_ANGLE = 16, //Specifies the minimum angular difference, in degrees, between two matches that have unique angles.
+ IMAQ_MINIMUM_MATCH_SEPARATION_SCALE = 17, //Specifies the minimum difference in scale, expressed as a percentage, between two matches that have unique scales.
+ IMAQ_MAXIMUM_MATCH_OVERLAP = 18, //Specifies whether you want the algorithm to spend less time accurately estimating the location of a match.
+ IMAQ_ENABLE_COARSE_RESULT = 19, //Specifies whether you want the algorithm to spend less time accurately estimating the location of a match.
+ IMAQ_ENABLE_CALIBRATION_SUPPORT = 20, //Specifies whether or not the algorithm treat the inspection image as a calibrated image.
+ IMAQ_ENABLE_CONTRAST_REVERSAL = 21, //Specifies the contrast of the matches to search for.
+ IMAQ_SEARCH_STRATEGY = 22, //Specifies the aggressiveness of the strategy used to find matches in the image.
+ IMAQ_REFINEMENT_MATCH_FACTOR = 23, //Specifies the factor applied to the number of matches requested to determine how many matches are refined in the pyramid stage.
+ IMAQ_SUBPIXEL_MATCH_FACTOR = 24, //Specifies the factor applied to the number for matches requested to determine how many matches are used for the final (subpixel) stage.
+ IMAQ_MAX_REFINEMENT_ITERATIONS = 25, //Specifies maximum refinement iteration.
+} GeometricSetupDataItem;
+
+typedef enum DistortionModel_enum {
+ IMAQ_POLYNOMIAL_MODEL = 0, //Polynomial model.
+ IMAQ_DIVISION_MODEL = 1, //Division Model.
+ IMAQ_NO_DISTORTION_MODEL = -1, //Not a distortion model.
+} DistortionModel;
+
+typedef enum CalibrationThumbnailType_enum {
+ IMAQ_CAMARA_MODEL_TYPE = 0, //Camara model thumbnail type.
+ IMAQ_PERSPECTIVE_TYPE = 1, //Perspective thumbnail type.
+ IMAQ_MICRO_PLANE_TYPE = 2, //Micro Plane thumbnail type.
+ IMAQ_CALIBRATION_THUMBNAIL_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} CalibrationThumbnailType;
+
+typedef enum SettingType_enum {
+ IMAQ_ROTATION_ANGLE_RANGE = 0, //Set a range for this option to specify the angles at which you expect the Function to find template matches in the inspection image.
+ IMAQ_SCALE_RANGE = 1, //Set a range for this option to specify the sizes at which you expect the Function to find template matches in the inspection image.
+ IMAQ_OCCLUSION_RANGE = 2, //Set a range for this option to specify the amount of occlusion you expect for a match in the inspection image.
+ IMAQ_SETTING_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} SettingType;
+
+typedef enum SegmentationDistanceLevel_enum {
+ IMAQ_SEGMENTATION_LEVEL_CONSERVATIVE = 0, //Uses extensive criteria to determine the Maximum Distance.
+ IMAQ_SEGMENTATION_LEVEL_AGGRESSIVE = 1, //Uses few criteria to determine the Maximum Distance.
+ IMAQ_SEGMENTATION_LEVEL_SIZE_GUARD = 0xFFFFFFFF
+} SegmentationDistanceLevel;
+
+typedef enum ExtractContourSelection_enum {
+ IMAQ_CLOSEST = 0, //Selects the curve closest to the ROI.
+ IMAQ_LONGEST = 1, //Selects the longest curve.
+ IMAQ_STRONGEST = 2, //Selects the curve with the highest edge strength averaged from each point on the curve.
+ IMAQ_EXTRACT_CONTOUR_SELECTION_SIZE_GUARD = 0xFFFFFFFF
+} ExtractContourSelection;
+
+typedef enum FindTransformMode_enum {
+ IMAQ_FIND_REFERENCE = 0, //Update both parts of the coordinate system.
+ IMAQ_UPDATE_TRANSFORM = 1, //Update only the new reference system.
+ IMAQ_FIND_TRANSFORM_MODE_SIZE_GUARD = 0xFFFFFFFF
+} FindTransformMode;
+
+typedef enum ExtractContourDirection_enum {
+ IMAQ_RECT_LEFT_RIGHT = 0, //Searches the ROI from left to right.
+ IMAQ_RECT_RIGHT_LEFT = 1, //Searches the ROI from right to left.
+ IMAQ_RECT_TOP_BOTTOM = 2, //Searches the ROI from top to bottom.
+ IMAQ_RECT_BOTTOM_TOP = 3, //Searches the ROI from bottom to top.
+ IMAQ_ANNULUS_INNER_OUTER = 4, //Searches the ROI from the inner radius to the outer radius.
+ IMAQ_ANNULUS_OUTER_INNER = 5, //Searches the ROI from the outer radius to the inner radius.
+ IMAQ_ANNULUS_START_STOP = 6, //Searches the ROI from start angle to end angle.
+ IMAQ_ANNULUS_STOP_START = 7, //Searches the ROI from end angle to start angle.
+ IMAQ_EXTRACT_CONTOUR_DIRECTION_SIZE_GUARD = 0xFFFFFFFF
+} ExtractContourDirection;
+
+typedef enum EdgePolaritySearchMode_enum {
+ IMAQ_SEARCH_FOR_ALL_EDGES = 0, //Searches for all edges.
+ IMAQ_SEARCH_FOR_RISING_EDGES = 1, //Searches for rising edges only.
+ IMAQ_SEARCH_FOR_FALLING_EDGES = 2, //Searches for falling edges only.
+ IMAQ_EDGE_POLARITY_MODE_SIZE_GUARD = 0xFFFFFFFF
+} EdgePolaritySearchMode;
+
+typedef enum Connectivity_enum {
+ IMAQ_FOUR_CONNECTED = 0, //Morphological reconstruction is performed in connectivity mode 4.
+ IMAQ_EIGHT_CONNECTED = 1, //Morphological reconstruction is performed in connectivity mode 8.
+ IMAQ_CONNECTIVITY_SIZE_GUARD = 0xFFFFFFFF
+} Connectivity;
+
+typedef enum MorphologyReconstructOperation_enum {
+ IMAQ_DILATE_RECONSTRUCT = 0, //Performs Reconstruction by dilation.
+ IMAQ_ERODE_RECONSTRUCT = 1, //Performs Reconstruction by erosion.
+ IMAQ_MORPHOLOGY_RECONSTRUCT_OPERATION_SIZE_GUARD = 0xFFFFFFFF
+} MorphologyReconstructOperation;
+
+typedef enum WaveletType_enum {
+ IMAQ_DB02 = 0,
+ IMAQ_DB03 = 1,
+ IMAQ_DB04 = 2, //Specifies the Wavelet Type as DB02.
+ IMAQ_DB05 = 3,
+ IMAQ_DB06 = 4,
+ IMAQ_DB07 = 5,
+ IMAQ_DB08 = 6,
+ IMAQ_DB09 = 7,
+ IMAQ_DB10 = 8,
+ IMAQ_DB11 = 9,
+ IMAQ_DB12 = 10,
+ IMAQ_DB13 = 11,
+ IMAQ_DB14 = 12,
+ IMAQ_HAAR = 13,
+ IMAQ_BIOR1_3 = 14,
+ IMAQ_BIOR1_5 = 15,
+ IMAQ_BIOR2_2 = 16,
+ IMAQ_BIOR2_4 = 17,
+ IMAQ_BIOR2_6 = 18,
+ IMAQ_BIOR2_8 = 19,
+ IMAQ_BIOR3_1 = 20,
+ IMAQ_BIOR3_3 = 21,
+ IMAQ_BIOR3_5 = 22,
+ IMAQ_BIOR3_7 = 23,
+ IMAQ_BIOR3_9 = 24,
+ IMAQ_BIOR4_4 = 25,
+ IMAQ_COIF1 = 26,
+ IMAQ_COIF2 = 27,
+ IMAQ_COIF3 = 28,
+ IMAQ_COIF4 = 29,
+ IMAQ_COIF5 = 30,
+ IMAQ_SYM2 = 31,
+ IMAQ_SYM3 = 32,
+ IMAQ_SYM4 = 33,
+ IMAQ_SYM5 = 34,
+ IMAQ_SYM6 = 35,
+ IMAQ_SYM7 = 36,
+ IMAQ_SYM8 = 37,
+ IMAQ_BIOR5_5 = 38,
+ IMAQ_BIOR6_8 = 39,
+ IMAQ_WAVE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} WaveletType;
+
+typedef enum ParticleClassifierThresholdType_enum {
+ IMAQ_THRESHOLD_MANUAL = 0, //The classifier performs a manual threshold on the image during preprocessing.
+ IMAQ_THRESHOLD_AUTO = 1, //The classifier performs an auto threshold on the image during preprocessing.
+ IMAQ_THRESHOLD_LOCAL = 2, //The classifier performs a local threshold on the image during preprocessing.
+} ParticleClassifierThresholdType;
+
+typedef enum MeasureParticlesCalibrationMode_enum {
+ IMAQ_CALIBRATION_MODE_PIXEL = 0, //The function takes only pixel measurements on the particles in the image.
+ IMAQ_CALIBRATION_MODE_CALIBRATED = 1, //The function takes only calibrated measurements on the particles in the image.
+ IMAQ_CALIBRATION_MODE_BOTH = 2, //The function takes both pixel and calibrated measurements on the particles in the image.
+ IMAQ_MEASURE_PARTICLES_CALIBRATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} MeasureParticlesCalibrationMode;
+
+typedef enum GeometricMatchingSearchStrategy_enum {
+ IMAQ_GEOMETRIC_MATCHING_CONSERVATIVE = 0, //Instructs the pattern matching algorithm to use the largest possible amount of information from the image at the expense of slowing down the speed of the algorithm.
+ IMAQ_GEOMETRIC_MATCHING_BALANCED = 1, //Instructs the pattern matching algorithm to balance the amount of information from the image it uses with the speed of the algorithm.
+ IMAQ_GEOMETRIC_MATCHING_AGGRESSIVE = 2, //Instructs the pattern matching algorithm to use a lower amount of information from the image, which allows the algorithm to run quickly but at the expense of accuracy.
+ IMAQ_GEOMETRIC_MATCHING_SEARCH_STRATEGY_SIZE_GUARD = 0xFFFFFFFF
+} GeometricMatchingSearchStrategy;
+
+typedef enum ColorClassificationResolution_enum {
+ IMAQ_CLASSIFIER_LOW_RESOLUTION = 0, //Low resolution version of the color classifier.
+ IMAQ_CLASSIFIER_MEDIUM_RESOLUTION = 1, //Medium resolution version of the color classifier.
+ IMAQ_CLASSIFIER_HIGH_RESOLUTION = 2, //High resolution version of the color classifier.
+ IMAQ_CLASSIFIER_RESOLUTION_SIZE_GUARD = 0xFFFFFFFF
+} ColorClassificationResolution;
+
+typedef enum ConnectionConstraintType_enum {
+ IMAQ_DISTANCE_CONSTRAINT = 0, //Specifies the distance, in pixels, within which the end points of two curves must lie in order to be considered part of a contour.
+ IMAQ_ANGLE_CONSTRAINT = 1, //Specifies the range, in degrees, within which the difference between the angle of two curves, measured at the end points, must lie in order for the two curves to be considered part of a contour.
+ IMAQ_CONNECTIVITY_CONSTRAINT = 2, //Specifies the distance, in pixels, within which a line extended from the end point of a curve must pass the end point of another curve in order for the two curves to be considered part of a contour.
+ IMAQ_GRADIENT_CONSTRAINT = 3, //Specifies the range, in degrees, within which the gradient angles of two curves, measured at the end points, must lie in order for the two curves to be considered part of a contour.
+ IMAQ_NUM_CONNECTION_CONSTRAINT_TYPES = 4, //.
+ IMAQ_CONNECTION_CONSTRAINT_SIZE_GUARD = 0xFFFFFFFF
+} ConnectionConstraintType;
+
+typedef enum Barcode2DContrast_enum {
+ IMAQ_ALL_BARCODE_2D_CONTRASTS = 0, //The function searches for barcodes of each contrast type.
+ IMAQ_BLACK_ON_WHITE_BARCODE_2D = 1, //The function searches for 2D barcodes containing black data on a white background.
+ IMAQ_WHITE_ON_BLACK_BARCODE_2D = 2, //The function searches for 2D barcodes containing white data on a black background.
+ IMAQ_BARCODE_2D_CONTRAST_SIZE_GUARD = 0xFFFFFFFF
+} Barcode2DContrast;
+
+typedef enum QRModelType_enum {
+ IMAQ_QR_MODELTYPE_AUTO_DETECT = 0, //Specifies that the function will auto-detect the type of QR code.
+ IMAQ_QR_MODELTYPE_MICRO = 1, //Specifies the QR code is of a micro type.
+ IMAQ_QR_MODELTYPE_MODEL1 = 2, //Specifies the QR code is of a model1 type.
+ IMAQ_QR_MODELTYPE_MODEL2 = 3, //Specifies the QR code is of a model2 type.
+ IMAQ_QR_MODEL_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} QRModelType;
+
+typedef enum WindowBackgroundFillStyle_enum {
+ IMAQ_FILL_STYLE_SOLID = 0, //Fill the display window with a solid color.
+ IMAQ_FILL_STYLE_HATCH = 2, //Fill the display window with a pattern defined by WindowBackgroundHatchStyle.
+ IMAQ_FILL_STYLE_DEFAULT = 3, //Fill the display window with the NI Vision default pattern.
+ IMAQ_FILL_STYLE_SIZE_GUARD = 0xFFFFFFFF
+} WindowBackgroundFillStyle;
+
+typedef enum ExtractionMode_enum {
+ IMAQ_NORMAL_IMAGE = 0, //Specifies that the function makes no assumptions about the uniformity of objects in the image or the image background.
+ IMAQ_UNIFORM_REGIONS = 1, //Specifies that the function assumes that either the objects in the image or the image background consists of uniform pixel values.
+ IMAQ_EXTRACTION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ExtractionMode;
+
+typedef enum EdgeFilterSize_enum {
+ IMAQ_FINE = 0, //Specifies that the function uses a fine (narrow) edge filter.
+ IMAQ_NORMAL = 1, //Specifies that the function uses a normal edge filter.
+ IMAQ_CONTOUR_TRACING = 2, //Sets the Edge Filter Size to contour tracing, which provides the best results for contour extraction but increases the time required to process the image.
+ IMAQ_EDGE_FILTER_SIZE_SIZE_GUARD = 0xFFFFFFFF
+} EdgeFilterSize;
+
+typedef enum Barcode2DSearchMode_enum {
+ IMAQ_SEARCH_MULTIPLE = 0, //The function searches for multiple 2D barcodes.
+ IMAQ_SEARCH_SINGLE_CONSERVATIVE = 1, //The function searches for 2D barcodes using the same searching algorithm as IMAQ_SEARCH_MULTIPLE but stops searching after locating one valid barcode.
+ IMAQ_SEARCH_SINGLE_AGGRESSIVE = 2, //The function searches for a single 2D barcode using a method that assumes the barcode occupies a majority of the search region.
+ IMAQ_BARCODE_2D_SEARCH_MODE_SIZE_GUARD = 0xFFFFFFFF
+} Barcode2DSearchMode;
+
+typedef enum DataMatrixSubtype_enum {
+ IMAQ_ALL_DATA_MATRIX_SUBTYPES = 0, //The function searches for Data Matrix barcodes of all subtypes.
+ IMAQ_DATA_MATRIX_SUBTYPES_ECC_000_ECC_140 = 1, //The function searches for Data Matrix barcodes of subtypes ECC 000, ECC 050, ECC 080, ECC 100 and ECC 140.
+ IMAQ_DATA_MATRIX_SUBTYPE_ECC_200 = 2, //The function searches for Data Matrix ECC 200 barcodes.
+ IMAQ_DATA_MATRIX_SUBTYPE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixSubtype;
+
+typedef enum FeatureType_enum {
+ IMAQ_NOT_FOUND_FEATURE = 0, //Specifies the feature is not found.
+ IMAQ_CIRCLE_FEATURE = 1, //Specifies the feature is a circle.
+ IMAQ_ELLIPSE_FEATURE = 2, //Specifies the feature is an ellipse.
+ IMAQ_CONST_CURVE_FEATURE = 3, //Specifies the features is a constant curve.
+ IMAQ_RECTANGLE_FEATURE = 4, //Specifies the feature is a rectangle.
+ IMAQ_LEG_FEATURE = 5, //Specifies the feature is a leg.
+ IMAQ_CORNER_FEATURE = 6, //Specifies the feature is a corner.
+ IMAQ_PARALLEL_LINE_PAIR_FEATURE = 7, //Specifies the feature is a parallel line pair.
+ IMAQ_PAIR_OF_PARALLEL_LINE_PAIRS_FEATURE = 8, //Specifies the feature is a pair of parallel line pairs.
+ IMAQ_LINE_FEATURE = 9, //Specifies the feature is a line.
+ IMAQ_CLOSED_CURVE_FEATURE = 10, //Specifies the feature is a closed curve.
+ IMAQ_FEATURE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} FeatureType;
+
+typedef enum Barcode2DCellShape_enum {
+ IMAQ_SQUARE_CELLS = 0, //The function uses an algorithm for decoding the 2D barcode that works with square data cells.
+ IMAQ_ROUND_CELLS = 1, //The function uses an algorithm for decoding the 2D barcode that works with round data cells.
+ IMAQ_BARCODE_2D_CELL_SHAPE_SIZE_GUARD = 0xFFFFFFFF
+} Barcode2DCellShape;
+
+typedef enum LocalThresholdMethod_enum {
+ IMAQ_NIBLACK = 0, //The function computes thresholds for each pixel based on its local statistics using the Niblack local thresholding algorithm.
+ IMAQ_BACKGROUND_CORRECTION = 1, //The function performs background correction first to eliminate non-uniform lighting effects, then performs thresholding using the Otsu thresholding algorithm.
+ IMAQ_LOCAL_THRESHOLD_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} LocalThresholdMethod;
+
+typedef enum Barcode2DType_enum {
+ IMAQ_PDF417 = 0, //The 2D barcode is of type PDF417.
+ IMAQ_DATA_MATRIX_ECC_000 = 1, //The 2D barcode is of type Data Matrix ECC 000.
+ IMAQ_DATA_MATRIX_ECC_050 = 2, //The 2D barcode is of type Data Matrix ECC 050.
+ IMAQ_DATA_MATRIX_ECC_080 = 3, //The 2D barcode is of type Data Matrix ECC 080.
+ IMAQ_DATA_MATRIX_ECC_100 = 4, //The 2D barcode is of type Data Matrix ECC 100.
+ IMAQ_DATA_MATRIX_ECC_140 = 5, //The 2D barcode is of type Data Matrix ECC 140.
+ IMAQ_DATA_MATRIX_ECC_200 = 6, //The 2D barcode is of type Data Matrix ECC 200.
+ IMAQ_BARCODE_2D_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} Barcode2DType;
+
+typedef enum ClassifierEngineType_enum {
+ IMAQ_ENGINE_NONE = 0, //No engine has been set on this classifier session.
+ IMAQ_ENGINE_NEAREST_NEIGHBOR = 1, //Nearest neighbor engine.
+ IMAQ_ENGINE_SUPPORT_VECTOR_MACHINE = 2,
+ IMAQ_CLASSIFIER_ENGINE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ClassifierEngineType;
+
+typedef enum ClassifierType_enum {
+ IMAQ_CLASSIFIER_CUSTOM = 0, //The classifier session classifies vectors of doubles.
+ IMAQ_CLASSIFIER_PARTICLE = 1, //The classifier session classifies particles in binary images.
+ IMAQ_CLASSIFIER_COLOR = 2, //The classifier session classifies an image based on its color.
+ IMAQ_CLASSIFIER_TEXTURE = 3, //The classifier session classifies an image based on its texture.
+ IMAQ_CLASSIFIER_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ClassifierType;
+
+typedef enum ParticleType_enum {
+ IMAQ_PARTICLE_BRIGHT = 0, //Bright particles.
+ IMAQ_PARTICLE_DARK = 1, //Dark particles.
+ IMAQ_PARTICLE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ParticleType;
+
+typedef enum VisionInfoType2_enum {
+ IMAQ_VISIONINFO_CALIBRATION = 0x01, //Used to indicate interaction with the Calibration information in an image.
+ IMAQ_VISIONINFO_OVERLAY = 0x02, //Used to indicate interaction with the Overlay information in an image.
+ IMAQ_VISIONINFO_GRAYTEMPLATE = 0x04, //Used to indicate interaction with the grayscale template information in an image.
+ IMAQ_VISIONINFO_COLORTEMPLATE = 0x08, //Used to indicate interaction with the color template information in an image.
+ IMAQ_VISIONINFO_GEOMETRICTEMPLATE = 0x10, //Used to indicate interaction with the geometric template information in an image.
+ IMAQ_VISIONINFO_CUSTOMDATA = 0x20, //Used to indicate interaction with the binary or text Custom Data in an image.
+ IMAQ_VISIONINFO_GOLDENTEMPLATE = 0x40, //Used to indicate interaction with the golden template information in an image.
+ IMAQ_VISIONINFO_GEOMETRICTEMPLATE2 = 0x80, //Used to indicate interaction with the geometric template 2 information in an image.
+ IMAQ_VISIONINFO_ALL = 0xFFFFFFFF, //Removes, checks for, or indicates the presence of all types of extra information in an image.
+} VisionInfoType2;
+
+typedef enum ReadClassifierFileMode_enum {
+ IMAQ_CLASSIFIER_READ_ALL = 0, //Read all information from the classifier file.
+ IMAQ_CLASSIFIER_READ_SAMPLES = 1, //Read only the samples from the classifier file.
+ IMAQ_CLASSIFIER_READ_PROPERTIES = 2, //Read only the properties from the classifier file.
+ IMAQ_READ_CLASSIFIER_FILE_MODES_SIZE_GUARD = 0xFFFFFFFF
+} ReadClassifierFileMode;
+
+typedef enum WriteClassifierFileMode_enum {
+ IMAQ_CLASSIFIER_WRITE_ALL = 0, //Writes all information to the classifier file.
+ IMAQ_CLASSIFIER_WRITE_CLASSIFY_ONLY = 1, //Write only the information needed to classify to the classifier file.
+ IMAQ_WRITE_CLASSIFIER_FILE_MODES_SIZE_GUARD = 0xFFFFFFFF
+} WriteClassifierFileMode;
+
+typedef enum Barcode2DShape_enum {
+ IMAQ_SQUARE_BARCODE_2D = 0, //The function searches for square 2D barcodes.
+ IMAQ_RECTANGULAR_BARCODE_2D = 1, //The function searches for rectangular 2D barcodes.
+ IMAQ_BARCODE_2D_SHAPE_SIZE_GUARD = 0xFFFFFFFF
+} Barcode2DShape;
+
+typedef enum DataMatrixRotationMode_enum {
+ IMAQ_UNLIMITED_ROTATION = 0, //The function allows for unlimited rotation.
+ IMAQ_0_DEGREES = 1, //The function allows for between -5 and 5 degrees of rotation.
+ IMAQ_90_DEGREES = 2, //The function allows for between 85 and 95 degrees of rotation.
+ IMAQ_180_DEGREES = 3, //The function allows for between 175 and 185 degrees of rotation.
+ IMAQ_270_DEGREES = 4, //The function allows for between 265 and 275 degrees of rotation.
+ IMAQ_DATA_MATRIX_ROTATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixRotationMode;
+
+typedef enum AIMGrade_enum {
+ IMAQ_AIM_GRADE_F = 0, //The Data Matrix barcode received a grade of F.
+ IMAQ_AIM_GRADE_D = 1, //The Data Matrix barcode received a grade of D.
+ IMAQ_AIM_GRADE_C = 2, //The Data Matrix barcode received a grade of C.
+ IMAQ_AIM_GRADE_B = 3, //The Data Matrix barcode received a grade of B.
+ IMAQ_AIM_GRADE_A = 4, //The Data Matrix barcode received a grade of A.
+ IMAQ_DATA_MATRIX_AIM_GRADE_SIZE_GUARD = 0xFFFFFFFF
+} AIMGrade;
+
+typedef enum DataMatrixCellFillMode_enum {
+ IMAQ_AUTO_DETECT_CELL_FILL_MODE = -2, //Sets the function to determine the Data Matrix barcode cell fill percentage automatically.
+ IMAQ_LOW_FILL = 0, //Sets the function to read Data Matrix barcodes with a cell fill percentage of less than 30 percent.
+ IMAQ_NORMAL_FILL = 1, //Sets the function to read Data Matrix barcodes with a cell fill percentage greater than or equal to 30 percent.
+ IMAQ_DATA_MATRIX_CELL_FILL_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixCellFillMode;
+
+typedef enum DataMatrixDemodulationMode_enum {
+ IMAQ_AUTO_DETECT_DEMODULATION_MODE = -2, //The function will try each demodulation mode and use the one which decodes the Data Matrix barcode within the fewest iterations and utilizing the least amount of error correction.
+ IMAQ_HISTOGRAM = 0, //The function uses a histogram of all of the Data Matrix cells to calculate a threshold.
+ IMAQ_LOCAL_CONTRAST = 1, //The function examines each of the cell's neighbors to determine if the cell is on or off.
+ IMAQ_COMBINED = 2, //The function uses the histogram of the Data Matrix barcode to calculate a threshold.
+ IMAQ_ALL_DEMODULATION_MODES = 3, //The function tries IMAQ_HISTOGRAM, then IMAQ_LOCAL_CONTRAST and then IMAQ_COMBINATION, stopping once one mode is successful.
+ IMAQ_DATA_MATRIX_DEMODULATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixDemodulationMode;
+
+typedef enum DataMatrixECC_enum {
+ IMAQ_AUTO_DETECT_ECC = -2, //Sets the function to determine the Data Matrix barcode ECC automatically.
+ IMAQ_ECC_000 = 0, //Sets the function to read Data Matrix barcodes of ECC 000 only.
+ IMAQ_ECC_050 = 50, //Sets the function to read Data Matrix barcodes of ECC 050 only.
+ IMAQ_ECC_080 = 80, //Sets the function to read Data Matrix barcodes of ECC 080 only.
+ IMAQ_ECC_100 = 100, //Sets the function to read Data Matrix barcodes of ECC 100 only.
+ IMAQ_ECC_140 = 140, //Sets the function to read Data Matrix barcodes of ECC 140 only.
+ IMAQ_ECC_000_140 = 190, //Sets the function to read Data Matrix barcodes of ECC 000, ECC 050, ECC 080, ECC 100, and ECC 140 only.
+ IMAQ_ECC_200 = 200, //Sets the function to read Data Matrix barcodes of ECC 200 only.
+ IMAQ_DATA_MATRIX_ECC_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixECC;
+
+typedef enum DataMatrixPolarity_enum {
+ IMAQ_AUTO_DETECT_POLARITY = -2, //Sets the function to determine the Data Matrix barcode polarity automatically.
+ IMAQ_BLACK_DATA_ON_WHITE_BACKGROUND = 0, //Sets the function to read Data Matrix barcodes with dark data on a bright background.
+ IMAQ_WHITE_DATA_ON_BLACK_BACKGROUND = 1, //Sets the function to read Data Matrix barcodes with bright data on a dark background.
+ IMAQ_DATA_MATRIX_POLARITY_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixPolarity;
+
+typedef enum DataMatrixCellFilterMode_enum {
+ IMAQ_AUTO_DETECT_CELL_FILTER_MODE = -2, //The function will try all filter modes and uses the one that decodes the Data Matrix barcode within the fewest iterations and utilizing the least amount of error correction.
+ IMAQ_AVERAGE_FILTER = 0, //The function sets the pixel value for the cell to the average of the sampled pixels.
+ IMAQ_MEDIAN_FILTER = 1, //The function sets the pixel value for the cell to the median of the sampled pixels.
+ IMAQ_CENTRAL_AVERAGE_FILTER = 2, //The function sets the pixel value for the cell to the average of the pixels in the center of the cell sample.
+ IMAQ_HIGH_AVERAGE_FILTER = 3, //The function sets the pixel value for the cell to the average value of the half of the sampled pixels with the highest pixel values.
+ IMAQ_LOW_AVERAGE_FILTER = 4, //The function sets the pixel value for the cell to the average value of the half of the sampled pixels with the lowest pixel values.
+ IMAQ_VERY_HIGH_AVERAGE_FILTER = 5, //The function sets the pixel value for the cell to the average value of the ninth of the sampled pixels with the highest pixel values.
+ IMAQ_VERY_LOW_AVERAGE_FILTER = 6, //The function sets the pixel value for the cell to the average value of the ninth of the sampled pixels with the lowest pixel values.
+ IMAQ_ALL_CELL_FILTERS = 8, //The function tries each filter mode, starting with IMAQ_AVERAGE_FILTER and ending with IMAQ_VERY_LOW_AVERAGE_FILTER, stopping once a filter mode decodes correctly.
+ IMAQ_DATA_MATRIX_CELL_FILTER_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixCellFilterMode;
+
+typedef enum WindowBackgroundHatchStyle_enum {
+ IMAQ_HATCH_STYLE_HORIZONTAL = 0, //The background of the display window will be horizontal bars.
+ IMAQ_HATCH_STYLE_VERTICAL = 1, //The background of the display window will be vertical bars.
+ IMAQ_HATCH_STYLE_FORWARD_DIAGONAL = 2, //The background of the display window will be diagonal bars.
+ IMAQ_HATCH_STYLE_BACKWARD_DIAGONAL = 3, //The background of the display window will be diagonal bars.
+ IMAQ_HATCH_STYLE_CROSS = 4, //The background of the display window will be intersecting horizontal and vertical bars.
+ IMAQ_HATCH_STYLE_CROSS_HATCH = 5, //The background of the display window will be intersecting forward and backward diagonal bars.
+ IMAQ_HATCH_STYLE_SIZE_GUARD = 0xFFFFFFFF
+} WindowBackgroundHatchStyle;
+
+typedef enum DataMatrixMirrorMode_enum {
+ IMAQ_AUTO_DETECT_MIRROR = -2, //Specifies that the function should determine if the Data Matrix barcode is mirrored.
+ IMAQ_APPEARS_NORMAL = 0, //Specifies that the function should expect the Data Matrix barcode to appear normal.
+ IMAQ_APPEARS_MIRRORED = 1, //Specifies that the function should expect the Data Matrix barcode to appear mirrored.
+ IMAQ_DATA_MATRIX_MIRROR_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixMirrorMode;
+
+typedef enum CalibrationMode2_enum {
+ IMAQ_PERSPECTIVE_MODE = 0, //Functions correct for distortion caused by the camera's perspective.
+ IMAQ_MICROPLANE_MODE = 1, //Functions correct for distortion caused by the camera's lens.
+ IMAQ_SIMPLE_CALIBRATION_MODE = 2, //Functions do not correct for distortion.
+ IMAQ_CORRECTED_IMAGE_MODE = 3, //The image is already corrected.
+ IMAQ_NO_CALIBRATION_MODE = 4, //Image with No calibration.
+ IMAQ_CALIBRATION_MODE2_SIZE_GUARD = 0xFFFFFFFF
+} CalibrationMode2;
+
+typedef enum DataMatrixGradingMode_enum {
+ IMAQ_NO_GRADING = 0, //The function does not make any preparatory calculations.
+ IMAQ_PREPARE_FOR_AIM = 1, //The function prepares the image for grading using the AIM Print Quality metrics.
+ IMAQ_DATA_MATRIX_GRADING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixGradingMode;
+
+typedef enum WaveletTransformMode_enum {
+ IMAQ_WAVELET_TRANSFORM_INTEGER = 0, //Uses a 5-3 reversible integer transform.
+ IMAQ_WAVELET_TRANSFORM_FLOATING_POINT = 1, //Performs a 9-7 irreversible floating-point transform.
+ IMAQ_WAVELET_TRANSFORM_MODE_SIZE_GUARD = 0xFFFFFFFF
+} WaveletTransformMode;
+
+typedef enum NormalizationMethod_enum {
+ IMAQ_NORMALIZATION_NONE = 0, //No normalization.
+ IMAQ_NORMALIZATION_HISTOGRAM_MATCHING = 1, //Adjust image so its histogram is similar to the golden template's histogram.
+ IMAQ_NORMALIZATION_AVERAGE_MATCHING = 2, //Adjust image so its mean pixel value equals the golden template's mean pixel value.
+ IMAQ_NORMALIZATION_SIZE_GUARD = 0xFFFFFFFF
+} NormalizationMethod;
+
+typedef enum RegistrationMethod_enum {
+ IMAQ_REGISTRATION_NONE = 0, //No registration.
+ IMAQ_REGISTRATION_PERSPECTIVE = 1, //Adjust image to correct for minor variations in alignment or perspective.
+ IMAQ_REGISTRATION_SIZE_GUARD = 0xFFFFFFFF
+} RegistrationMethod;
+
+typedef enum LinearAveragesMode_enum {
+ IMAQ_COLUMN_AVERAGES = 1, //Specifies that the function calculates the mean pixel value of each column.
+ IMAQ_ROW_AVERAGES = 2, //Specifies that the function calculates the mean pixel value of each row.
+ IMAQ_RISING_DIAGONAL_AVERAGES = 4, //Specifies that the function calculates the mean pixel value of each diagonal running from the lower left to the upper right of the inspected area of the image.
+ IMAQ_FALLING_DIAGONAL_AVERAGES = 8, //Specifies that the function calculates the mean pixel value of each diagonal running from the upper left to the lower right of the inspected area of the image.
+ IMAQ_ALL_LINEAR_AVERAGES = 15, //Specifies that the function calculates all four linear mean pixel values.
+ IMAQ_LINEAR_AVERAGES_MODE_SIZE_GUARD = 0xFFFFFFFF
+} LinearAveragesMode;
+
+typedef enum CompressionType_enum {
+ IMAQ_COMPRESSION_NONE = 0, //Specifies that the function should not compress the image.
+ IMAQ_COMPRESSION_JPEG = 1, //Specifies that the function should use lossy JPEG compression on the image.
+ IMAQ_COMPRESSION_PACKED_BINARY = 2, //Specifies that the function should use lossless binary packing on the image.
+ IMAQ_COMPRESSION_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} CompressionType;
+
+typedef enum FlattenType_enum {
+ IMAQ_FLATTEN_IMAGE = 0, //Flattens just the image data.
+ IMAQ_FLATTEN_IMAGE_AND_VISION_INFO = 1, //Flattens the image data and any Vision information associated with the image.
+ IMAQ_FLATTEN_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} FlattenType;
+
+typedef enum DataMatrixCellSampleSize_enum {
+ IMAQ_AUTO_DETECT_CELL_SAMPLE_SIZE = -2, //The function will try each sample size and use the one which decodes the Data Matrix barcode within the fewest iterations and utilizing the least amount of error correction.
+ IMAQ_1x1 = 1, //The function will use a 1x1 sized sample from each cell.
+ IMAQ_2x2 = 2, //The function will use a 2x2 sized sample from each cell.
+ IMAQ_3x3 = 3, //The function will use a 3x3 sized sample from each cell.
+ IMAQ_4x4 = 4, //The function will use a 4x4 sized sample from each cell.
+ IMAQ_5x5 = 5, //The function will use a 5x5 sized sample from each cell.
+ IMAQ_6x6 = 6, //The function will use a 6x6 sized sample from each cell.
+ IMAQ_7x7 = 7, //The function will use a 7x7 sized sample from each cell.
+ IMAQ_DATA_MATRIX_CELL_SAMPLE_SIZE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixCellSampleSize;
+
+
+//============================================================================
+// Forward Declare Data Structures
+//============================================================================
+typedef struct Image_struct Image;
+typedef struct ROI_struct ROI;
+typedef struct Overlay_struct Overlay;
+typedef struct ClassifierSession_struct ClassifierSession;
+typedef struct MultipleGeometricPattern_struct MultipleGeometricPattern;
+typedef int ContourID;
+typedef unsigned long SESSION_ID;
+typedef int AVISession;
+typedef char* FilterName;
+typedef char String255[256];
+typedef struct CharSet_struct CharSet;
+typedef struct OCRSpacingOptions_struct OCRSpacingOptions;
+typedef struct OCRProcessingOptions_struct OCRProcessingOptions;
+typedef struct ReadTextOptions_struct ReadTextOptions;
+typedef struct CharInfo_struct CharInfo;
+typedef struct CharReport_struct CharReport;
+typedef struct ReadTextReport_struct ReadTextReport;
+typedef struct DivisionModel_struct DivisionModel;
+typedef struct FocalLength_struct FocalLength;
+typedef struct PolyModel_struct PolyModel;
+typedef struct DistortionModelParams_struct DistortionModelParams;
+typedef struct PointFloat_struct PointFloat;
+typedef struct InternalParameters_struct InternalParameters;
+typedef struct MaxGridSize_struct MaxGridSize;
+typedef struct ImageSize_struct ImageSize;
+typedef struct CalibrationReferencePoints_struct CalibrationReferencePoints;
+typedef struct GetCameraParametersReport_struct GetCameraParametersReport;
+typedef struct CalibrationAxisInfo_struct CalibrationAxisInfo;
+typedef struct CalibrationLearnSetupInfo_struct CalibrationLearnSetupInfo;
+typedef struct GridDescriptor_struct GridDescriptor;
+typedef struct ErrorStatistics_struct ErrorStatistics;
+typedef struct GetCalibrationInfoReport_struct GetCalibrationInfoReport;
+typedef struct EdgePolarity_struct EdgePolarity;
+typedef struct ClampSettings_struct ClampSettings;
+typedef struct PointDouble_struct PointDouble;
+typedef struct PointDoublePair_struct PointDoublePair;
+typedef struct ClampResults_struct ClampResults;
+typedef struct ClampPoints_struct ClampPoints;
+typedef struct RGBValue_struct RGBValue;
+typedef struct ClampOverlaySettings_struct ClampOverlaySettings;
+typedef struct ClampMax2Report_struct ClampMax2Report;
+typedef struct ContourFitSplineReport_struct ContourFitSplineReport;
+typedef struct LineFloat_struct LineFloat;
+typedef struct LineEquation_struct LineEquation;
+typedef struct ContourFitLineReport_struct ContourFitLineReport;
+typedef struct ContourFitPolynomialReport_struct ContourFitPolynomialReport;
+typedef struct PartialCircle_struct PartialCircle;
+typedef struct PartialEllipse_struct PartialEllipse;
+typedef struct SetupMatchPatternData_struct SetupMatchPatternData;
+typedef struct RangeSettingDouble_struct RangeSettingDouble;
+typedef struct GeometricAdvancedSetupDataOption_struct GeometricAdvancedSetupDataOption;
+typedef struct ContourInfoReport_struct ContourInfoReport;
+typedef struct ROILabel_struct ROILabel;
+typedef struct SupervisedColorSegmentationReport_struct SupervisedColorSegmentationReport;
+typedef struct LabelToROIReport_struct LabelToROIReport;
+typedef struct ColorSegmenationOptions_struct ColorSegmenationOptions;
+typedef struct ClassifiedCurve_struct ClassifiedCurve;
+typedef struct RangeDouble_struct RangeDouble;
+typedef struct RangeLabel_struct RangeLabel;
+typedef struct CurvatureAnalysisReport_struct CurvatureAnalysisReport;
+typedef struct Disparity_struct Disparity;
+typedef struct ComputeDistancesReport_struct ComputeDistancesReport;
+typedef struct MatchMode_struct MatchMode;
+typedef struct ClassifiedDisparity_struct ClassifiedDisparity;
+typedef struct ClassifyDistancesReport_struct ClassifyDistancesReport;
+typedef struct ContourComputeCurvatureReport_struct ContourComputeCurvatureReport;
+typedef struct ContourOverlaySettings_struct ContourOverlaySettings;
+typedef struct CurveParameters_struct CurveParameters;
+typedef struct ExtractContourReport_struct ExtractContourReport;
+typedef struct ConnectionConstraint_struct ConnectionConstraint;
+typedef struct ExtractTextureFeaturesReport_struct ExtractTextureFeaturesReport;
+typedef struct WaveletBandsReport_struct WaveletBandsReport;
+typedef struct CircleFitOptions_struct CircleFitOptions;
+typedef struct EdgeOptions2_struct EdgeOptions2;
+typedef struct FindCircularEdgeOptions_struct FindCircularEdgeOptions;
+typedef struct FindConcentricEdgeOptions_struct FindConcentricEdgeOptions;
+typedef struct ConcentricEdgeFitOptions_struct ConcentricEdgeFitOptions;
+typedef struct FindConcentricEdgeReport_struct FindConcentricEdgeReport;
+typedef struct FindCircularEdgeReport_struct FindCircularEdgeReport;
+typedef struct WindowSize_struct WindowSize;
+typedef struct DisplacementVector_struct DisplacementVector;
+typedef struct WaveletOptions_struct WaveletOptions;
+typedef struct CooccurrenceOptions_struct CooccurrenceOptions;
+typedef struct ParticleClassifierLocalThresholdOptions_struct ParticleClassifierLocalThresholdOptions;
+typedef struct RangeFloat_struct RangeFloat;
+typedef struct ParticleClassifierAutoThresholdOptions_struct ParticleClassifierAutoThresholdOptions;
+typedef struct ParticleClassifierPreprocessingOptions2_struct ParticleClassifierPreprocessingOptions2;
+typedef struct MeasureParticlesReport_struct MeasureParticlesReport;
+typedef struct GeometricPatternMatch3_struct GeometricPatternMatch3;
+typedef struct MatchGeometricPatternAdvancedOptions3_struct MatchGeometricPatternAdvancedOptions3;
+typedef struct ColorOptions_struct ColorOptions;
+typedef struct SampleScore_struct SampleScore;
+typedef struct ClassifierReportAdvanced_struct ClassifierReportAdvanced;
+typedef struct LearnGeometricPatternAdvancedOptions2_struct LearnGeometricPatternAdvancedOptions2;
+typedef struct ParticleFilterOptions2_struct ParticleFilterOptions2;
+typedef struct FindEdgeOptions2_struct FindEdgeOptions2;
+typedef struct FindEdgeReport_struct FindEdgeReport;
+typedef struct FindTransformRectOptions2_struct FindTransformRectOptions2;
+typedef struct FindTransformRectsOptions2_struct FindTransformRectsOptions2;
+typedef struct ReadTextReport3_struct ReadTextReport3;
+typedef struct CharacterStatistics_struct CharacterStatistics;
+typedef struct CharReport3_struct CharReport3;
+typedef struct ArcInfo2_struct ArcInfo2;
+typedef struct EdgeReport2_struct EdgeReport2;
+typedef struct SearchArcInfo_struct SearchArcInfo;
+typedef struct ConcentricRakeReport2_struct ConcentricRakeReport2;
+typedef struct SpokeReport2_struct SpokeReport2;
+typedef struct EdgeInfo_struct EdgeInfo;
+typedef struct SearchLineInfo_struct SearchLineInfo;
+typedef struct RakeReport2_struct RakeReport2;
+typedef struct TransformBehaviors_struct TransformBehaviors;
+typedef struct QRCodeDataToken_struct QRCodeDataToken;
+typedef struct ParticleFilterOptions_struct ParticleFilterOptions;
+typedef struct StraightEdgeReport2_struct StraightEdgeReport2;
+typedef struct StraightEdgeOptions_struct StraightEdgeOptions;
+typedef struct StraightEdge_struct StraightEdge;
+typedef struct QRCodeSearchOptions_struct QRCodeSearchOptions;
+typedef struct QRCodeSizeOptions_struct QRCodeSizeOptions;
+typedef struct QRCodeDescriptionOptions_struct QRCodeDescriptionOptions;
+typedef struct QRCodeReport_struct QRCodeReport;
+typedef struct AIMGradeReport_struct AIMGradeReport;
+typedef struct DataMatrixSizeOptions_struct DataMatrixSizeOptions;
+typedef struct DataMatrixDescriptionOptions_struct DataMatrixDescriptionOptions;
+typedef struct DataMatrixSearchOptions_struct DataMatrixSearchOptions;
+typedef struct DataMatrixReport_struct DataMatrixReport;
+typedef struct JPEG2000FileAdvancedOptions_struct JPEG2000FileAdvancedOptions;
+typedef struct MatchGeometricPatternAdvancedOptions2_struct MatchGeometricPatternAdvancedOptions2;
+typedef struct InspectionAlignment_struct InspectionAlignment;
+typedef struct InspectionOptions_struct InspectionOptions;
+typedef struct CharReport2_struct CharReport2;
+typedef struct CharInfo2_struct CharInfo2;
+typedef struct ReadTextReport2_struct ReadTextReport2;
+typedef struct EllipseFeature_struct EllipseFeature;
+typedef struct CircleFeature_struct CircleFeature;
+typedef struct ConstCurveFeature_struct ConstCurveFeature;
+typedef struct RectangleFeature_struct RectangleFeature;
+typedef struct LegFeature_struct LegFeature;
+typedef struct CornerFeature_struct CornerFeature;
+typedef struct LineFeature_struct LineFeature;
+typedef struct ParallelLinePairFeature_struct ParallelLinePairFeature;
+typedef struct PairOfParallelLinePairsFeature_struct PairOfParallelLinePairsFeature;
+typedef union GeometricFeature_union GeometricFeature;
+typedef struct FeatureData_struct FeatureData;
+typedef struct GeometricPatternMatch2_struct GeometricPatternMatch2;
+typedef struct ClosedCurveFeature_struct ClosedCurveFeature;
+typedef struct LineMatch_struct LineMatch;
+typedef struct LineDescriptor_struct LineDescriptor;
+typedef struct RectangleDescriptor_struct RectangleDescriptor;
+typedef struct RectangleMatch_struct RectangleMatch;
+typedef struct EllipseDescriptor_struct EllipseDescriptor;
+typedef struct EllipseMatch_struct EllipseMatch;
+typedef struct CircleMatch_struct CircleMatch;
+typedef struct CircleDescriptor_struct CircleDescriptor;
+typedef struct ShapeDetectionOptions_struct ShapeDetectionOptions;
+typedef struct Curve_struct Curve;
+typedef struct CurveOptions_struct CurveOptions;
+typedef struct Barcode2DInfo_struct Barcode2DInfo;
+typedef struct DataMatrixOptions_struct DataMatrixOptions;
+typedef struct ClassifierAccuracyReport_struct ClassifierAccuracyReport;
+typedef struct NearestNeighborClassResult_struct NearestNeighborClassResult;
+typedef struct NearestNeighborTrainingReport_struct NearestNeighborTrainingReport;
+typedef struct ParticleClassifierPreprocessingOptions_struct ParticleClassifierPreprocessingOptions;
+typedef struct ClassifierSampleInfo_struct ClassifierSampleInfo;
+typedef struct ClassScore_struct ClassScore;
+typedef struct ClassifierReport_struct ClassifierReport;
+typedef struct NearestNeighborOptions_struct NearestNeighborOptions;
+typedef struct ParticleClassifierOptions_struct ParticleClassifierOptions;
+typedef struct RGBU64Value_struct RGBU64Value;
+typedef struct GeometricPatternMatch_struct GeometricPatternMatch;
+typedef struct MatchGeometricPatternAdvancedOptions_struct MatchGeometricPatternAdvancedOptions;
+typedef struct MatchGeometricPatternOptions_struct MatchGeometricPatternOptions;
+typedef struct LearnGeometricPatternAdvancedOptions_struct LearnGeometricPatternAdvancedOptions;
+typedef struct FitEllipseOptions_struct FitEllipseOptions;
+typedef struct FitCircleOptions_struct FitCircleOptions;
+typedef struct ConstructROIOptions2_struct ConstructROIOptions2;
+typedef struct HSLValue_struct HSLValue;
+typedef struct HSVValue_struct HSVValue;
+typedef struct HSIValue_struct HSIValue;
+typedef struct CIELabValue_struct CIELabValue;
+typedef struct CIEXYZValue_struct CIEXYZValue;
+typedef union Color2_union Color2;
+typedef struct BestEllipse2_struct BestEllipse2;
+typedef struct LearnPatternAdvancedOptions_struct LearnPatternAdvancedOptions;
+typedef struct AVIInfo_struct AVIInfo;
+typedef struct LearnPatternAdvancedShiftOptions_struct LearnPatternAdvancedShiftOptions;
+typedef struct LearnPatternAdvancedRotationOptions_struct LearnPatternAdvancedRotationOptions;
+typedef struct MatchPatternAdvancedOptions_struct MatchPatternAdvancedOptions;
+typedef struct ParticleFilterCriteria2_struct ParticleFilterCriteria2;
+typedef struct BestCircle2_struct BestCircle2;
+typedef struct OCRSpacingOptions_struct OCRSpacingOptions;
+typedef struct OCRProcessingOptions_struct OCRProcessingOptions;
+typedef struct ReadTextOptions_struct ReadTextOptions;
+typedef struct CharInfo_struct CharInfo;
+#if !defined(USERINT_HEADER) && !defined(_CVI_RECT_DEFINED)
+typedef struct Rect_struct Rect;
+#endif
+typedef struct CharReport_struct CharReport;
+typedef struct ReadTextReport_struct ReadTextReport;
+#if !defined(USERINT_HEADER) && !defined(_CVI_POINT_DEFINED)
+typedef struct Point_struct Point;
+#endif
+typedef struct Annulus_struct Annulus;
+typedef struct EdgeLocationReport_struct EdgeLocationReport;
+typedef struct EdgeOptions_struct EdgeOptions;
+typedef struct EdgeReport_struct EdgeReport;
+typedef struct ExtremeReport_struct ExtremeReport;
+typedef struct FitLineOptions_struct FitLineOptions;
+typedef struct DisplayMapping_struct DisplayMapping;
+typedef struct DetectExtremesOptions_struct DetectExtremesOptions;
+typedef struct ImageInfo_struct ImageInfo;
+typedef struct LCDOptions_struct LCDOptions;
+typedef struct LCDReport_struct LCDReport;
+typedef struct LCDSegments_struct LCDSegments;
+typedef struct LearnCalibrationOptions_struct LearnCalibrationOptions;
+typedef struct LearnColorPatternOptions_struct LearnColorPatternOptions;
+typedef struct Line_struct Line;
+typedef struct LinearAverages_struct LinearAverages;
+typedef struct LineProfile_struct LineProfile;
+typedef struct MatchColorPatternOptions_struct MatchColorPatternOptions;
+typedef struct HistogramReport_struct HistogramReport;
+typedef struct ArcInfo_struct ArcInfo;
+typedef struct AxisReport_struct AxisReport;
+typedef struct BarcodeInfo_struct BarcodeInfo;
+typedef struct BCGOptions_struct BCGOptions;
+typedef struct BestCircle_struct BestCircle;
+typedef struct BestEllipse_struct BestEllipse;
+typedef struct BestLine_struct BestLine;
+typedef struct BrowserOptions_struct BrowserOptions;
+typedef struct CoordinateSystem_struct CoordinateSystem;
+typedef struct CalibrationInfo_struct CalibrationInfo;
+typedef struct CalibrationPoints_struct CalibrationPoints;
+typedef struct CaliperOptions_struct CaliperOptions;
+typedef struct CaliperReport_struct CaliperReport;
+typedef struct DrawTextOptions_struct DrawTextOptions;
+typedef struct CircleReport_struct CircleReport;
+typedef struct ClosedContour_struct ClosedContour;
+typedef struct ColorHistogramReport_struct ColorHistogramReport;
+typedef struct ColorInformation_struct ColorInformation;
+typedef struct Complex_struct Complex;
+typedef struct ConcentricRakeReport_struct ConcentricRakeReport;
+typedef struct ConstructROIOptions_struct ConstructROIOptions;
+typedef struct ContourInfo_struct ContourInfo;
+typedef union ContourUnion_union ContourUnion;
+typedef struct ContourInfo2_struct ContourInfo2;
+typedef struct ContourPoint_struct ContourPoint;
+typedef struct CoordinateTransform_struct CoordinateTransform;
+typedef struct CoordinateTransform2_struct CoordinateTransform2;
+typedef struct CannyOptions_struct CannyOptions;
+typedef struct Range_struct Range;
+typedef struct UserPointSymbol_struct UserPointSymbol;
+typedef struct View3DOptions_struct View3DOptions;
+typedef struct MatchPatternOptions_struct MatchPatternOptions;
+typedef struct TIFFFileOptions_struct TIFFFileOptions;
+typedef union Color_union Color;
+typedef union PixelValue_union PixelValue;
+typedef struct OpenContour_struct OpenContour;
+typedef struct OverlayTextOptions_struct OverlayTextOptions;
+typedef struct ParticleFilterCriteria_struct ParticleFilterCriteria;
+typedef struct ParticleReport_struct ParticleReport;
+typedef struct PatternMatch_struct PatternMatch;
+typedef struct QuantifyData_struct QuantifyData;
+typedef struct QuantifyReport_struct QuantifyReport;
+typedef struct RakeOptions_struct RakeOptions;
+typedef struct RakeReport_struct RakeReport;
+typedef struct TransformReport_struct TransformReport;
+typedef struct ShapeReport_struct ShapeReport;
+typedef struct MeterArc_struct MeterArc;
+typedef struct ThresholdData_struct ThresholdData;
+typedef struct StructuringElement_struct StructuringElement;
+typedef struct SpokeReport_struct SpokeReport;
+typedef struct SimpleEdgeOptions_struct SimpleEdgeOptions;
+typedef struct SelectParticleCriteria_struct SelectParticleCriteria;
+typedef struct SegmentInfo_struct SegmentInfo;
+typedef struct RotationAngleRange_struct RotationAngleRange;
+typedef struct RotatedRect_struct RotatedRect;
+typedef struct ROIProfile_struct ROIProfile;
+typedef struct ToolWindowOptions_struct ToolWindowOptions;
+typedef struct SpokeOptions_struct SpokeOptions;
+
+//============================================================================
+// Data Structures
+//============================================================================
+#if !defined __GNUC__ && !defined _M_X64
+#pragma pack(push,1)
+#endif
+typedef struct DivisionModel_struct {
+ float kappa; //The learned kappa coefficient of division model.
+} DivisionModel;
+
+typedef struct FocalLength_struct {
+ float fx; //Focal length in X direction.
+ float fy; //Focal length in Y direction.
+} FocalLength;
+
+typedef struct PolyModel_struct {
+ float* kCoeffs; //The learned radial coefficients of polynomial model.
+ unsigned int numKCoeffs; //Number of K coefficients.
+ float p1; //The P1(learned tangential coefficients of polynomial model).
+ float p2; //The P2(learned tangential coefficients of polynomial model).
+} PolyModel;
+
+typedef struct DistortionModelParams_struct {
+ DistortionModel distortionModel; //Type of learned distortion model.
+ PolyModel polyModel; //The learned coefficients of polynomial model.
+ DivisionModel divisionModel; //The learned coefficient of division model.
+} DistortionModelParams;
+
+typedef struct PointFloat_struct {
+ float x; //The x-coordinate of the point.
+ float y; //The y-coordinate of the point.
+} PointFloat;
+
+typedef struct InternalParameters_struct {
+ char isInsufficientData;
+ FocalLength focalLength;
+ PointFloat opticalCenter;
+} InternalParameters;
+
+typedef struct MaxGridSize_struct {
+ unsigned int xMax; //Maximum x limit for the grid size.
+ unsigned int yMax; //Maximum y limit for the grid size.
+} MaxGridSize;
+
+typedef struct ImageSize_struct {
+ unsigned int xRes; //X resolution of the image.
+ unsigned int yRes; //Y resolution of the image.
+} ImageSize;
+
+typedef struct CalibrationReferencePoints_struct {
+ PointDouble* pixelCoords; //Specifies the coordinates of the pixel reference points.
+ unsigned int numPixelCoords; //Number of pixel coordinates.
+ PointDouble* realCoords; //Specifies the measuring unit associated with the image.
+ unsigned int numRealCoords; //Number of real coordinates.
+ CalibrationUnit units; //Specifies the units of X Step and Y Step.
+ ImageSize imageSize; //Specifies the size of calibration template image.
+} CalibrationReferencePoints;
+
+typedef struct GetCameraParametersReport_struct {
+ double* projectionMatrix; //The projection(homography) matrix of working plane.
+ unsigned int projectionMatrixRows; //Number of rows in projection matrix.
+ unsigned int projectionMatrixCols; //Number of columns in projection matrix.
+ DistortionModelParams distortion; //Distortion model Coefficients.
+ InternalParameters internalParams; //The learned internal paramters of camera model such as focal length and optical center.
+} GetCameraParametersReport;
+
+typedef struct CalibrationAxisInfo_struct {
+ PointFloat center; //The origin of the reference coordinate system, expressed in pixel units.
+ float rotationAngle; //The angle of the x-axis of the real-world coordinate system, in relation to the horizontal.
+ AxisOrientation axisDirection; //Specifies the direction of the calibraiton axis which is either Direct or Indirect.
+} CalibrationAxisInfo;
+
+typedef struct CalibrationLearnSetupInfo_struct {
+ CalibrationMode2 calibrationMethod; //Type of calibration method used.
+ DistortionModel distortionModel; //Type of learned distortion model.
+ ScalingMethod scaleMode; //The aspect scaling to use when correcting an image.
+ CalibrationROI roiMode; //The ROI to use when correcting an image.
+ char learnCorrectionTable; //Set this input to true value if you want the correction table to be determined and stored.
+} CalibrationLearnSetupInfo;
+
+typedef struct GridDescriptor_struct {
+ float xStep; //The distance in the x direction between two adjacent pixels in units specified by unit.
+ float yStep; //The distance in the y direction between two adjacent pixels in units specified by unit.
+ CalibrationUnit unit; //The unit of measure for the image.
+} GridDescriptor;
+
+typedef struct ErrorStatistics_struct {
+ double mean; //Mean error statistics value.
+ double maximum; //Maximum value of error.
+ double standardDeviation; //The standard deviation error statistiscs value.
+ double distortion; //The distortion error statistics value.
+} ErrorStatistics;
+
+typedef struct GetCalibrationInfoReport_struct {
+ ROI* userRoi; //Specifies the ROI the user provided when learning the calibration.
+ ROI* calibrationRoi; //Specifies the ROI that corresponds to the region of the image where the calibration information is accurate.
+ CalibrationAxisInfo axisInfo; //Reference Coordinate System for the real-world coordinates.
+ CalibrationLearnSetupInfo learnSetupInfo; //Calibration learn setup information.
+ GridDescriptor gridDescriptor; //Specifies scaling constants used to calibrate the image.
+ float* errorMap; //The the error map of calibration template image.
+ unsigned int errorMapRows; //Number of rows in error map.
+ unsigned int errorMapCols; //Number of Columns in error map.
+ ErrorStatistics errorStatistics; //Error statistics of the calibration.
+} GetCalibrationInfoReport;
+
+typedef struct EdgePolarity_struct {
+ EdgePolaritySearchMode start;
+ EdgePolaritySearchMode end;
+} EdgePolarity;
+
+typedef struct ClampSettings_struct {
+ double angleRange; //Specifies the angle range.
+ EdgePolarity edgePolarity; //Specifies the edge polarity.
+} ClampSettings;
+
+typedef struct PointDouble_struct {
+ double x; //The x-coordinate of the point.
+ double y; //The y-coordinate of the point.
+} PointDouble;
+
+typedef struct PointDoublePair_struct {
+ PointDouble start; //The Start co-ordinate of the pair.
+ PointDouble end; //The End co-ordinate of the pair.
+} PointDoublePair;
+
+typedef struct ClampResults_struct {
+ double distancePix; //Defines the Pixel world distance.
+ double distanceRealWorld; //Defines the real world distance.
+ double angleAbs; //Defines the absolute angle.
+ double angleRelative; //Defines the relative angle.
+} ClampResults;
+
+typedef struct ClampPoints_struct {
+ PointDoublePair pixel; //Specifies the pixel world point pair for clamp.
+ PointDoublePair realWorld; //Specifies the real world point pair for clamp.
+} ClampPoints;
+
+typedef struct RGBValue_struct {
+ unsigned char B; //The blue value of the color.
+ unsigned char G; //The green value of the color.
+ unsigned char R; //The red value of the color.
+ unsigned char alpha; //The alpha value of the color, which represents extra information about a color image, such as gamma correction.
+} RGBValue;
+
+typedef struct ClampOverlaySettings_struct {
+ int showSearchArea; //If TRUE, the function overlays the search area on the image.
+ int showCurves; //If TRUE, the function overlays the curves on the image.
+ int showClampLocation; //If TRUE, the function overlays the clamp location on the image.
+ int showResult; //If TRUE, the function overlays the hit lines to the object and the edge used to generate the hit line on the result image.
+ RGBValue searchAreaColor; //Specifies the RGB color value to use to overlay the search area.
+ RGBValue curvesColor; //Specifies the RGB color value to use to overlay the curves.
+ RGBValue clampLocationsColor; //Specifies the RGB color value to use to overlay the clamp locations.
+ RGBValue resultColor; //Specifies the RGB color value to use to overlay the results.
+ char* overlayGroupName; //Specifies the group overlay name for the step overlays.
+} ClampOverlaySettings;
+
+typedef struct ClampMax2Report_struct {
+ ClampResults clampResults; //Specifies the Clamp results information returned by the function.
+ ClampPoints clampPoints; //Specifies the clamp points information returned by the function.
+ unsigned int calibrationValid; //Specifies if the calibration information is valid or not.
+} ClampMax2Report;
+
+typedef struct ContourFitSplineReport_struct {
+ PointDouble* points; //It returns the points of the best-fit B-spline curve.
+ int numberOfPoints; //Number of Best fit points returned.
+} ContourFitSplineReport;
+
+typedef struct LineFloat_struct {
+ PointFloat start; //The coordinate location of the start of the line.
+ PointFloat end; //The coordinate location of the end of the line.
+} LineFloat;
+
+typedef struct LineEquation_struct {
+ double a; //The a coefficient of the line equation.
+ double b; //The b coefficient of the line equation.
+ double c; //The c coefficient of the line equation.
+} LineEquation;
+
+typedef struct ContourFitLineReport_struct {
+ LineFloat lineSegment; //Line Segment represents the intersection of the line equation and the contour.
+ LineEquation lineEquation; //Line Equation is a structure of three coefficients A, B, and C of the equation in the normal form (Ax + By + C=0) of the best fit line.
+} ContourFitLineReport;
+
+typedef struct ContourFitPolynomialReport_struct {
+ PointDouble* bestFit; //It returns the points of the best-fit polynomial.
+ int numberOfPoints; //Number of Best fit points returned.
+ double* polynomialCoefficients; //Polynomial Coefficients returns the coefficients of the polynomial equation.
+ int numberOfCoefficients; //Number of Coefficients returned in the polynomial coefficients array.
+} ContourFitPolynomialReport;
+
+typedef struct PartialCircle_struct {
+ PointFloat center; //Center of the circle.
+ double radius; //Radius of the circle.
+ double startAngle; //Start angle of the fitted structure.
+ double endAngle; //End angle of the fitted structure.
+} PartialCircle;
+
+typedef struct PartialEllipse_struct {
+ PointFloat center; //Center of the Ellipse.
+ double angle; //Angle of the ellipse.
+ double majorRadius; //The length of the semi-major axis of the ellipse.
+ double minorRadius; //The length of the semi-minor axis of the ellipse.
+ double startAngle; //Start angle of the fitted structure.
+ double endAngle; //End angle of the fitted structure.
+} PartialEllipse;
+
+typedef struct SetupMatchPatternData_struct {
+ unsigned char* matchSetupData; //String containing the match setup data.
+ int numMatchSetupData; //Number of match setup data.
+} SetupMatchPatternData;
+
+typedef struct RangeSettingDouble_struct {
+ SettingType settingType; //Match Constraints specifies the match option whose values you want to constrain by the given range.
+ double min; //Min is the minimum value of the range for a given Match Constraint.
+ double max; //Max is the maximum value of the range for a given Match Constraint.
+} RangeSettingDouble;
+
+typedef struct GeometricAdvancedSetupDataOption_struct {
+ GeometricSetupDataItem type; //It determines the option you want to use during the matching phase.
+ double value; //Value is the value for the option you want to use during the matching phase.
+} GeometricAdvancedSetupDataOption;
+
+typedef struct ContourInfoReport_struct {
+ PointDouble* pointsPixel; //Points (pixel) specifies the location of every point detected on the curve, in pixels.
+ unsigned int numPointsPixel; //Number of points pixel elements.
+ PointDouble* pointsReal; //Points (real) specifies the location of every point detected on the curve, in calibrated units.
+ unsigned int numPointsReal; //Number of points real elements.
+ double* curvaturePixel; //Curvature Pixel displays the curvature profile for the selected contour, in pixels.
+ unsigned int numCurvaturePixel; //Number of curvature pixels.
+ double* curvatureReal; //Curvature Real displays the curvature profile for the selected contour, in calibrated units.
+ unsigned int numCurvatureReal; //Number of curvature Real elements.
+ double length; //Length (pixel) specifies the length, in pixels, of the curves in the image.
+ double lengthReal; //Length (real) specifies the length, in calibrated units, of the curves within the curvature range.
+ unsigned int hasEquation; //Has Equation specifies whether the contour has a fitted equation.
+} ContourInfoReport;
+
+typedef struct ROILabel_struct {
+ char* className; //Specifies the classname you want to segment.
+ unsigned int label; //Label is the label number associated with the Class Name.
+} ROILabel;
+
+typedef struct SupervisedColorSegmentationReport_struct {
+ ROILabel* labelOut; //The Roi labels array.
+ unsigned int numLabelOut; //The number of elements in labelOut array.
+} SupervisedColorSegmentationReport;
+
+typedef struct LabelToROIReport_struct {
+ ROI** roiArray; //Array of ROIs.
+ unsigned int numOfROIs; //Number of ROIs in the roiArray.
+ unsigned int* labelsOutArray; //Array of labels.
+ unsigned int numOfLabels; //Number of labels.
+ int* isTooManyVectorsArray; //isTooManyVectorsArray array.
+ unsigned int isTooManyVectorsArraySize; //Number of elements in isTooManyVectorsArray.
+} LabelToROIReport;
+
+typedef struct ColorSegmenationOptions_struct {
+ unsigned int windowX; //X is the window size in x direction.
+ unsigned int windowY; //Y is the window size in y direction.
+ unsigned int stepSize; //Step Size is the distance between two windows.
+ unsigned int minParticleArea; //Min Particle Area is the minimum number of allowed pixels.
+ unsigned int maxParticleArea; //Max Particle Area is the maximum number of allowed pixels.
+ short isFineSegment; //When enabled, the step processes the boundary pixels of each segmentation cluster using a step size of 1.
+} ColorSegmenationOptions;
+
+typedef struct ClassifiedCurve_struct {
+ double length; //Specifies the length, in pixels, of the curves within the curvature range.
+ double lengthReal; //specifies the length, in calibrated units, of the curves within the curvature range.
+ double maxCurvature; //specifies the maximum curvature, in pixels, for the selected curvature range.
+ double maxCurvatureReal; //specifies the maximum curvature, in calibrated units, for the selected curvature range.
+ unsigned int label; //specifies the class to which the the sample belongs.
+ PointDouble* curvePoints; //Curve Points is a point-coordinate cluster that defines the points of the curve.
+ unsigned int numCurvePoints; //Number of curve points.
+} ClassifiedCurve;
+
+typedef struct RangeDouble_struct {
+ double minValue; //The minimum value of the range.
+ double maxValue; //The maximum value of the range.
+} RangeDouble;
+
+typedef struct RangeLabel_struct {
+ RangeDouble range; //Specifies the range of curvature values.
+ unsigned int label; //Class Label specifies the class to which the the sample belongs.
+} RangeLabel;
+
+typedef struct CurvatureAnalysisReport_struct {
+ ClassifiedCurve* curves;
+ unsigned int numCurves;
+} CurvatureAnalysisReport;
+
+typedef struct Disparity_struct {
+ PointDouble current; //Current is a array of points that defines the target contour.
+ PointDouble reference; //reference is a array of points that defines the template contour.
+ double distance; //Specifies the distance, in pixels, between the template contour point and the target contour point.
+} Disparity;
+
+typedef struct ComputeDistancesReport_struct {
+ Disparity* distances; //Distances is an array containing the computed distances.
+ unsigned int numDistances; //Number elements in the distances array.
+ Disparity* distancesReal; //Distances Real is an array containing the computed distances in calibrated units.
+ unsigned int numDistancesReal; //Number of elements in real distances array.
+} ComputeDistancesReport;
+
+typedef struct MatchMode_struct {
+ unsigned int rotation; //Rotation When enabled, the Function searches for occurrences of the template in the inspection image, allowing for template matches to be rotated.
+ unsigned int scale; //Rotation When enabled, the Function searches for occurrences of the template in the inspection image, allowing for template matches to be rotated.
+ unsigned int occlusion; //Occlusion specifies whether or not to search for occluded versions of the shape.
+} MatchMode;
+
+typedef struct ClassifiedDisparity_struct {
+ double length; //Length (pixel) specifies the length, in pixels, of the curves within the curvature range.
+ double lengthReal; //Length (real) specifies the length, in calibrated units, of the curves within the curvature range.
+ double maxDistance; //Maximum Distance (pixel) specifies the maximum distance, in pixels, between points along the selected contour and the template contour.
+ double maxDistanceReal; //Maximum Distance (real) specifies the maximum distance, in calibrated units, between points along the selected contour and the template contour.
+ unsigned int label; //Class Label specifies the class to which the the sample belongs.
+ PointDouble* templateSubsection; //Template subsection points is an array of points that defines the boundary of the template.
+ unsigned int numTemplateSubsection; //Number of reference points.
+ PointDouble* targetSubsection; //Current Points(Target subsection points) is an array of points that defines the boundary of the target.
+ unsigned int numTargetSubsection; //Number of current points.
+} ClassifiedDisparity;
+
+typedef struct ClassifyDistancesReport_struct {
+ ClassifiedDisparity* classifiedDistances; //Disparity array containing the classified distances.
+ unsigned int numClassifiedDistances; //Number of elements in the disparity array.
+} ClassifyDistancesReport;
+
+typedef struct ContourComputeCurvatureReport_struct {
+ double* curvaturePixel; //Curvature Pixel displays the curvature profile for the selected contour, in pixels.
+ unsigned int numCurvaturePixel; //Number of curvature pixels.
+ double* curvatureReal; //Curvature Real displays the curvature profile for the selected contour, in calibrated units.
+ unsigned int numCurvatureReal; //Number of curvature Real elements.
+} ContourComputeCurvatureReport;
+
+typedef struct ContourOverlaySettings_struct {
+ unsigned int overlay; //Overlay specifies whether to display the overlay on the image.
+ RGBValue color; //Color is the color of the overlay.
+ unsigned int width; //Width specifies the width of the overlay in pixels.
+ unsigned int maintainWidth; //Maintain Width? specifies whether you want the overlay measured in screen pixels or image pixels.
+} ContourOverlaySettings;
+
+typedef struct CurveParameters_struct {
+ ExtractionMode extractionMode; //Specifies the method the function uses to identify curves in the image.
+ int threshold; //Specifies the minimum contrast a seed point must have in order to begin a curve.
+ EdgeFilterSize filterSize; //Specifies the width of the edge filter the function uses to identify curves in the image.
+ int minLength; //Specifies the length, in pixels, of the smallest curve the function will extract.
+ int searchStep; //Search Step Size specifies the distance, in the y direction, between the image rows that the algorithm inspects for curve seed points.
+ int maxEndPointGap; //Specifies the maximum gap, in pixels, between the endpoints of a curve that the function identifies as a closed curve.
+ int subpixel; //Subpixel specifies whether to detect curve points with subpixel accuracy.
+} CurveParameters;
+
+typedef struct ExtractContourReport_struct {
+ PointDouble* contourPoints; //Contour Points specifies every point found on the contour.
+ int numContourPoints; //Number of contour points.
+ PointDouble* sourcePoints; //Source Image Points specifies every point found on the contour in the source image.
+ int numSourcePoints; //Number of source points.
+} ExtractContourReport;
+
+typedef struct ConnectionConstraint_struct {
+ ConnectionConstraintType constraintType; //Constraint Type specifies what criteria to use to consider two curves part of a contour.
+ RangeDouble range; //Specifies range for a given Match Constraint.
+} ConnectionConstraint;
+
+typedef struct ExtractTextureFeaturesReport_struct {
+ int* waveletBands; //The array having all the Wavelet Banks used for extraction.
+ int numWaveletBands; //Number of wavelet banks in the Array.
+ double** textureFeatures; //2-D array to store all the Texture features extracted.
+ int textureFeaturesRows; //Number of Rows in the Texture Features array.
+ int textureFeaturesCols; //Number of Cols in Texture Features array.
+} ExtractTextureFeaturesReport;
+
+typedef struct WaveletBandsReport_struct {
+ float** LLBand; //2-D array for LL Band.
+ float** LHBand; //2-D array for LH Band.
+ float** HLBand; //2-D array for HL Band.
+ float** HHBand; //2-D array for HH Band.
+ float** LLLBand; //2-D array for LLL Band.
+ float** LLHBand; //2-D array for LLH Band.
+ float LHLBand; //2-D array for LHL Band.
+ float** LHHBand; //2-D array for LHH Band.
+ int rows; //Number of Rows for each of the 2-D arrays.
+ int cols; //Number of Columns for each of the 2-D arrays.
+} WaveletBandsReport;
+
+typedef struct CircleFitOptions_struct {
+ int maxRadius; //Specifies the acceptable distance, in pixels, that a point determined to belong to the circle can be from the perimeter of the circle.
+ double stepSize; //Step Size is the angle, in degrees, between each radial line in the annular region.
+ RakeProcessType processType; //Method used to process the data extracted for edge detection.
+} CircleFitOptions;
+
+typedef struct EdgeOptions2_struct {
+ EdgePolaritySearchMode polarity; //Specifies the polarity of the edges to be found.
+ unsigned int kernelSize; //Specifies the size of the edge detection kernel.
+ unsigned int width; //Specifies the number of pixels averaged perpendicular to the search direction to compute the edge profile strength at each point along the search ROI.
+ float minThreshold; //Specifies the minimum edge strength (gradient magnitude) required for a detected edge.
+ InterpolationMethod interpolationType; //Specifies the interpolation method used to locate the edge position.
+ ColumnProcessingMode columnProcessingMode; //Specifies the method used to find the straight edge.
+} EdgeOptions2;
+
+typedef struct FindCircularEdgeOptions_struct {
+ SpokeDirection direction; //Specifies the Spoke direction to search in the ROI.
+ int showSearchArea; //If TRUE, the function overlays the search area on the image.
+ int showSearchLines; //If TRUE, the function overlays the search lines used to locate the edges on the image.
+ int showEdgesFound; //If TRUE, the function overlays the locations of the edges found on the image.
+ int showResult; //If TRUE, the function overlays the hit lines to the object and the edge used to generate the hit line on the result image.
+ RGBValue searchAreaColor; //Specifies the RGB color value to use to overlay the search area.
+ RGBValue searchLinesColor; //Specifies the RGB color value to use to overlay the search lines.
+ RGBValue searchEdgesColor; //Specifies the RGB color value to use to overlay the search edges.
+ RGBValue resultColor; //Specifies the RGB color value to use to overlay the results.
+ char* overlayGroupName; //Specifies the overlay group name to assign to the overlays.
+ EdgeOptions2 edgeOptions; //Specifies the edge detection options along a single search line.
+} FindCircularEdgeOptions;
+
+typedef struct FindConcentricEdgeOptions_struct {
+ ConcentricRakeDirection direction; //Specifies the Concentric Rake direction.
+ int showSearchArea; //If TRUE, the function overlays the search area on the image.
+ int showSearchLines; //If TRUE, the function overlays the search lines used to locate the edges on the image.
+ int showEdgesFound; //If TRUE, the function overlays the locations of the edges found on the image.
+ int showResult; //If TRUE, the function overlays the hit lines to the object and the edge used to generate the hit line on the result image.
+ RGBValue searchAreaColor; //Specifies the RGB color value to use to overlay the search area.
+ RGBValue searchLinesColor; //Specifies the RGB color value to use to overlay the search lines.
+ RGBValue searchEdgesColor; //Specifies the RGB color value to use to overlay the search edges.
+ RGBValue resultColor; //Specifies the RGB color value to use to overlay the results.
+ char* overlayGroupName; //Specifies the overlay group name to assign to the overlays.
+ EdgeOptions2 edgeOptions; //Specifies the edge detection options along a single search line.
+} FindConcentricEdgeOptions;
+
+typedef struct ConcentricEdgeFitOptions_struct {
+ int maxRadius; //Specifies the acceptable distance, in pixels, that a point determined to belong to the circle can be from the perimeter of the circle.
+ double stepSize; //The sampling factor that determines the gap between the rake lines.
+ RakeProcessType processType; //Method used to process the data extracted for edge detection.
+} ConcentricEdgeFitOptions;
+
+typedef struct FindConcentricEdgeReport_struct {
+ PointFloat startPt; //Pixel Coordinates for starting point of the edge.
+ PointFloat endPt; //Pixel Coordinates for end point of the edge.
+ PointFloat startPtCalibrated; //Real world Coordinates for starting point of the edge.
+ PointFloat endPtCalibrated; //Real world Coordinates for end point of the edge.
+ double angle; //Angle of the edge found.
+ double angleCalibrated; //Calibrated angle of the edge found.
+ double straightness; //The straightness value of the detected straight edge.
+ double avgStrength; //Average strength of the egde found.
+ double avgSNR; //Average SNR(Signal to Noise Ratio) for the edge found.
+ int lineFound; //If the edge is found or not.
+} FindConcentricEdgeReport;
+
+typedef struct FindCircularEdgeReport_struct {
+ PointFloat centerCalibrated; //Real world Coordinates of the Center.
+ double radiusCalibrated; //Real world radius of the Circular Edge found.
+ PointFloat center; //Pixel Coordinates of the Center.
+ double radius; //Radius in pixels of the Circular Edge found.
+ double roundness; //The roundness of the calculated circular edge.
+ double avgStrength; //Average strength of the egde found.
+ double avgSNR; //Average SNR(Signal to Noise Ratio) for the edge found.
+ int circleFound; //If the circlular edge is found or not.
+} FindCircularEdgeReport;
+
+typedef struct WindowSize_struct {
+ int x; //Window lenght on X direction.
+ int y; //Window lenght on Y direction.
+ int stepSize; //Distance between windows.
+} WindowSize;
+
+typedef struct DisplacementVector_struct {
+ int x; //length on X direction.
+ int y; //length on Y direction.
+} DisplacementVector;
+
+typedef struct WaveletOptions_struct {
+ WaveletType typeOfWavelet; //Type of wavelet(db, bior.
+ float minEnergy; //Minimum Energy in the bands to consider for texture defect detection.
+} WaveletOptions;
+
+typedef struct CooccurrenceOptions_struct {
+ int level; //Level/size of matrix.
+ DisplacementVector displacement; //Displacemnet between pixels to accumulate the matrix.
+} CooccurrenceOptions;
+
+typedef struct ParticleClassifierLocalThresholdOptions_struct {
+ LocalThresholdMethod method; //Specifies the local thresholding method the function uses.
+ ParticleType particleType; //Specifies what kind of particles to look for.
+ unsigned int windowWidth; //The width of the rectangular window around the pixel on which the function performs the local threshold.
+ unsigned int windowHeight; //The height of the rectangular window around the pixel on which the function performs the local threshold.
+ double deviationWeight; //Specifies the k constant used in the Niblack local thresholding algorithm, which determines the weight applied to the variance calculation.
+} ParticleClassifierLocalThresholdOptions;
+
+typedef struct RangeFloat_struct {
+ float minValue; //The minimum value of the range.
+ float maxValue; //The maximum value of the range.
+} RangeFloat;
+
+typedef struct ParticleClassifierAutoThresholdOptions_struct {
+ ThresholdMethod method; //The method for binary thresholding, which specifies how to calculate the classes.
+ ParticleType particleType; //Specifies what kind of particles to look for.
+ RangeFloat limits; //The limits on the automatic threshold range.
+} ParticleClassifierAutoThresholdOptions;
+
+typedef struct ParticleClassifierPreprocessingOptions2_struct {
+ ParticleClassifierThresholdType thresholdType; //The type of threshold to perform on the image.
+ RangeFloat manualThresholdRange; //The range of pixels to keep if manually thresholding the image.
+ ParticleClassifierAutoThresholdOptions autoThresholdOptions; //The options used to auto threshold the image.
+ ParticleClassifierLocalThresholdOptions localThresholdOptions; //The options used to local threshold the image.
+ int rejectBorder; //Set this element to TRUE to reject border particles.
+ int numErosions; //The number of erosions to perform.
+} ParticleClassifierPreprocessingOptions2;
+
+typedef struct MeasureParticlesReport_struct {
+ double** pixelMeasurements; //The measurements on the particles in the image, in pixel coordinates.
+ double** calibratedMeasurements; //The measurements on the particles in the image, in real-world coordinates.
+ size_t numParticles; //The number of particles on which measurements were taken.
+ size_t numMeasurements; //The number of measurements taken.
+} MeasureParticlesReport;
+
+typedef struct GeometricPatternMatch3_struct {
+ PointFloat position; //The location of the origin of the template in the match.
+ float rotation; //The rotation of the match relative to the template image, in degrees.
+ float scale; //The size of the match relative to the size of the template image, expressed as a percentage.
+ float score; //The accuracy of the match.
+ PointFloat corner[4]; //An array of four points describing the rectangle surrounding the template image.
+ int inverse; //This element is TRUE if the match is an inverse of the template image.
+ float occlusion; //The percentage of the match that is occluded.
+ float templateMatchCurveScore; //The accuracy of the match obtained by comparing the template curves to the curves in the match region.
+ float matchTemplateCurveScore; //The accuracy of the match obtained by comparing the curves in the match region to the template curves.
+ float correlationScore; //The accuracy of the match obtained by comparing the template image to the match region using a correlation metric that compares the two regions as a function of their pixel values.
+ PointFloat calibratedPosition; //The location of the origin of the template in the match.
+ float calibratedRotation; //The rotation of the match relative to the template image, in degrees.
+ PointFloat calibratedCorner[4]; //An array of four points describing the rectangle surrounding the template image.
+} GeometricPatternMatch3;
+
+typedef struct MatchGeometricPatternAdvancedOptions3_struct {
+ unsigned int subpixelIterations; //Specifies the maximum number of incremental improvements used to refine matches with subpixel information.
+ double subpixelTolerance; //Specifies the maximum amount of change, in pixels, between consecutive incremental improvements in the match position before the function stops refining the match position.
+ unsigned int initialMatchListLength; //Specifies the maximum size of the match list.
+ int targetTemplateCurveScore; //Set this element to TRUE to specify that the function should calculate the match curve to template curve score and return it for each match result.
+ int correlationScore; //Set this element to TRUE to specify that the function should calculate the correlation score and return it for each match result.
+ double minMatchSeparationDistance; //Specifies the minimum separation distance, in pixels, between the origins of two matches that have unique positions.
+ double minMatchSeparationAngle; //Specifies the minimum angular difference, in degrees, between two matches that have unique angles.
+ double minMatchSeparationScale; //Specifies the minimum difference in scale, expressed as a percentage, between two matches that have unique scales.
+ double maxMatchOverlap; //Specifies the maximum amount of overlap, expressed as a percentage, allowed between the bounding rectangles of two unique matches.
+ int coarseResult; //Specifies whether you want the function to spend less time accurately estimating the location of a match.
+ int enableCalibrationSupport; //Set this element to TRUE to specify the algorithm treat the inspection image as a calibrated image.
+ ContrastMode enableContrastReversal; //Use this element to specify the contrast of the matches to search for in the image.
+ GeometricMatchingSearchStrategy matchStrategy; //Specifies the aggressiveness of the search strategy.
+ unsigned int refineMatchFactor; //Specifies the factor that is applied to the number of matches requested by the user to determine the number of matches that are refined at the initial matching stage.
+ unsigned int subpixelMatchFactor; //Specifies the factor that is applied to the number of matches requested by the user to determine the number of matches that are evaluated at the final subpixel matching stage.
+} MatchGeometricPatternAdvancedOptions3;
+
+typedef struct ColorOptions_struct {
+ ColorClassificationResolution colorClassificationResolution; //Specifies the color resolution of the classifier.
+ unsigned int useLuminance; //Specifies if the luminance band is going to be used in the feature vector.
+ ColorMode colorMode; //Specifies the color mode of the classifier.
+} ColorOptions;
+
+typedef struct SampleScore_struct {
+ char* className; //The name of the class.
+ float distance; //The distance from the item to this class.
+ unsigned int index; //index of this sample.
+} SampleScore;
+
+typedef struct ClassifierReportAdvanced_struct {
+ char* bestClassName; //The name of the best class for the sample.
+ float classificationScore; //The similarity of the sample and the two closest classes in the classifier.
+ float identificationScore; //The similarity of the sample and the assigned class.
+ ClassScore* allScores; //All classes and their scores.
+ int allScoresSize; //The number of entries in allScores.
+ SampleScore* sampleScores; //All samples and their scores.
+ int sampleScoresSize; //The number of entries in sampleScores.
+} ClassifierReportAdvanced;
+
+typedef struct LearnGeometricPatternAdvancedOptions2_struct {
+ double minScaleFactor; //Specifies the minimum scale factor that the template is learned for.
+ double maxScaleFactor; //Specifies the maximum scale factor the template is learned for.
+ double minRotationAngleValue; //Specifies the minimum rotation angle the template is learned for.
+ double maxRotationAngleValue; //Specifies the maximum rotation angle the template is learned for.
+ unsigned int imageSamplingFactor; //Specifies the factor that is used to subsample the template and the image for the initial matching phase.
+} LearnGeometricPatternAdvancedOptions2;
+
+typedef struct ParticleFilterOptions2_struct {
+ int rejectMatches; //Set this parameter to TRUE to transfer only those particles that do not meet all the criteria.
+ int rejectBorder; //Set this element to TRUE to reject border particles.
+ int fillHoles; //Set this element to TRUE to fill holes in particles.
+ int connectivity8; //Set this parameter to TRUE to use connectivity-8 to determine whether particles are touching.
+} ParticleFilterOptions2;
+
+typedef struct FindEdgeOptions2_struct {
+ RakeDirection direction; //The direction to search in the ROI.
+ int showSearchArea; //If TRUE, the function overlays the search area on the image.
+ int showSearchLines; //If TRUE, the function overlays the search lines used to locate the edges on the image.
+ int showEdgesFound; //If TRUE, the function overlays the locations of the edges found on the image.
+ int showResult; //If TRUE, the function overlays the hit lines to the object and the edge used to generate the hit line on the result image.
+ RGBValue searchAreaColor; //Specifies the RGB color value to use to overlay the search area.
+ RGBValue searchLinesColor; //Specifies the RGB color value to use to overlay the search lines.
+ RGBValue searchEdgesColor; //Specifies the RGB color value to use to overlay the search edges.
+ RGBValue resultColor; //Specifies the RGB color value to use to overlay the results.
+ char* overlayGroupName; //Specifies the overlay group name to assign to the overlays.
+ EdgeOptions2 edgeOptions; //Specifies the edge detection options along a single search line.
+} FindEdgeOptions2;
+
+typedef struct FindEdgeReport_struct {
+ StraightEdge* straightEdges; //An array of straight edges detected.
+ unsigned int numStraightEdges; //Indicates the number of straight edges found.
+} FindEdgeReport;
+
+typedef struct FindTransformRectOptions2_struct {
+ FindReferenceDirection direction; //Specifies the direction and orientation in which the function searches for the primary axis.
+ int showSearchArea; //If TRUE, the function overlays the search area on the image.
+ int showSearchLines; //If TRUE, the function overlays the search lines used to locate the edges on the image.
+ int showEdgesFound; //If TRUE, the function overlays the locations of the edges found on the image.
+ int showResult; //If TRUE, the function overlays the hit lines to the object and the edge used to generate the hit line on the result image.
+ RGBValue searchAreaColor; //Specifies the RGB color value to use to overlay the search area.
+ RGBValue searchLinesColor; //Specifies the RGB color value to use to overlay the search lines.
+ RGBValue searchEdgesColor; //Specifies the RGB color value to use to overlay the search edges.
+ RGBValue resultColor; //Specifies the RGB color value to use to overlay the results.
+ char* overlayGroupName; //Specifies the overlay group name to assign to the overlays.
+ EdgeOptions2 edgeOptions; //Specifies the edge detection options along a single search line.
+} FindTransformRectOptions2;
+
+typedef struct FindTransformRectsOptions2_struct {
+ FindReferenceDirection direction; //Specifies the direction and orientation in which the function searches for the primary axis.
+ int showSearchArea; //If TRUE, the function overlays the search area on the image.
+ int showSearchLines; //If TRUE, the function overlays the search lines used to locate the edges on the image.
+ int showEdgesFound; //If TRUE, the function overlays the locations of the edges found on the image.
+ int showResult; //If TRUE, the function overlays the hit lines to the object and the edge used to generate the hit line on the result image.
+ RGBValue searchAreaColor; //Specifies the RGB color value to use to overlay the search area.
+ RGBValue searchLinesColor; //Specifies the RGB color value to use to overlay the search lines.
+ RGBValue searchEdgesColor; //Specifies the RGB color value to use to overlay the search edges.
+ RGBValue resultColor; //Specifies the RGB color value to use to overlay the results.
+ char* overlayGroupName; //Specifies the overlay group name to assign to the overlays.
+ EdgeOptions2 primaryEdgeOptions; //Specifies the parameters used to compute the edge gradient information and detect the edges for the primary ROI.
+ EdgeOptions2 secondaryEdgeOptions; //Specifies the parameters used to compute the edge gradient information and detect the edges for the secondary ROI.
+} FindTransformRectsOptions2;
+
+typedef struct ReadTextReport3_struct {
+ const char* readString; //The read string.
+ CharReport3* characterReport; //An array of reports describing the properties of each identified character.
+ int numCharacterReports; //The number of identified characters.
+ ROI* roiBoundingCharacters; //An array specifying the coordinates of the character bounding ROI.
+} ReadTextReport3;
+
+typedef struct CharacterStatistics_struct {
+ int left; //The left offset of the character bounding rectangles in the current ROI.
+ int top; //The top offset of the character bounding rectangles in the current ROI.
+ int width; //The width of each of the characters you trained in the current ROI.
+ int height; //The height of each trained character in the current ROI.
+ int characterSize; //The size of the character in pixels.
+} CharacterStatistics;
+
+typedef struct CharReport3_struct {
+ const char* character; //The character value.
+ int classificationScore; //The degree to which the assigned character class represents the object better than the other character classes in the character set.
+ int verificationScore; //The similarity of the character and the reference character for the character class.
+ int verified; //This element is TRUE if a reference character was found for the character class and FALSE if a reference character was not found.
+ int lowThreshold; //The minimum value of the threshold range used for this character.
+ int highThreshold; //The maximum value of the threshold range used for this character.
+ CharacterStatistics characterStats; //Describes the characters segmented in the ROI.
+} CharReport3;
+
+typedef struct ArcInfo2_struct {
+ PointFloat center; //The center point of the arc.
+ double radius; //The radius of the arc.
+ double startAngle; //The starting angle of the arc, specified counter-clockwise from the x-axis.
+ double endAngle; //The ending angle of the arc, specified counter-clockwise from the x-axis.
+} ArcInfo2;
+
+typedef struct EdgeReport2_struct {
+ EdgeInfo* edges; //An array of edges detected.
+ unsigned int numEdges; //Indicates the number of edges detected.
+ double* gradientInfo; //An array that contains the calculated edge strengths along the user-defined search area.
+ unsigned int numGradientInfo; //Indicates the number of elements contained in gradientInfo.
+ int calibrationValid; //Indicates if the calibration data corresponding to the location of the edges is correct.
+} EdgeReport2;
+
+typedef struct SearchArcInfo_struct {
+ ArcInfo2 arcCoordinates; //Describes the arc used for edge detection.
+ EdgeReport2 edgeReport; //Describes the edges found in this search line.
+} SearchArcInfo;
+
+typedef struct ConcentricRakeReport2_struct {
+ EdgeInfo* firstEdges; //The first edge point detected along each search line in the ROI.
+ unsigned int numFirstEdges; //The number of points in the firstEdges array.
+ EdgeInfo* lastEdges; //The last edge point detected along each search line in the ROI.
+ unsigned int numLastEdges; //The number of points in the lastEdges array.
+ SearchArcInfo* searchArcs; //Contains the arcs used for edge detection and the edge information for each arc.
+ unsigned int numSearchArcs; //The number of arcs in the searchArcs array.
+} ConcentricRakeReport2;
+
+typedef struct SpokeReport2_struct {
+ EdgeInfo* firstEdges; //The first edge point detected along each search line in the ROI.
+ unsigned int numFirstEdges; //The number of points in the firstEdges array.
+ EdgeInfo* lastEdges; //The last edge point detected along each search line in the ROI.
+ unsigned int numLastEdges; //The number of points in the lastEdges array.
+ SearchLineInfo* searchLines; //The search lines used for edge detection.
+ unsigned int numSearchLines; //The number of search lines used in the edge detection.
+} SpokeReport2;
+
+typedef struct EdgeInfo_struct {
+ PointFloat position; //The location of the edge in the image.
+ PointFloat calibratedPosition; //The position of the edge in the image in real-world coordinates.
+ double distance; //The location of the edge from the first point along the boundary of the input ROI.
+ double calibratedDistance; //The location of the edge from the first point along the boundary of the input ROI in real-world coordinates.
+ double magnitude; //The intensity contrast at the edge.
+ double noisePeak; //The strength of the noise associated with the current edge.
+ int rising; //Indicates the polarity of the edge.
+} EdgeInfo;
+
+typedef struct SearchLineInfo_struct {
+ LineFloat lineCoordinates; //The endpoints of the search line.
+ EdgeReport2 edgeReport; //Describes the edges found in this search line.
+} SearchLineInfo;
+
+typedef struct RakeReport2_struct {
+ EdgeInfo* firstEdges; //The first edge point detected along each search line in the ROI.
+ unsigned int numFirstEdges; //The number of points in the firstEdges array.
+ EdgeInfo* lastEdges; //The last edge point detected along each search line in the ROI.
+ unsigned int numLastEdges; //The number of points in the lastEdges array.
+ SearchLineInfo* searchLines; //The search lines used for edge detection.
+ unsigned int numSearchLines; //The number of search lines used in the edge detection.
+} RakeReport2;
+
+typedef struct TransformBehaviors_struct {
+ GroupBehavior ShiftBehavior; //Specifies the behavior of an overlay group when a shift operation is applied to an image.
+ GroupBehavior ScaleBehavior; //Specifies the behavior of an overlay group when a scale operation is applied to an image.
+ GroupBehavior RotateBehavior; //Specifies the behavior of an overlay group when a rotate operation is applied to an image.
+ GroupBehavior SymmetryBehavior; //Specifies the behavior of an overlay group when a symmetry operation is applied to an image.
+} TransformBehaviors;
+
+typedef struct QRCodeDataToken_struct {
+ QRStreamMode mode; //Specifies the stream mode or the format of the data that is encoded in the QR code.
+ unsigned int modeData; //Indicates specifiers used by the user to postprocess the data if it requires it.
+ unsigned char* data; //Shows the encoded data in the QR code.
+ unsigned int dataLength; //Specifies the length of the data found in the QR code.
+} QRCodeDataToken;
+
+typedef struct ParticleFilterOptions_struct {
+ int rejectMatches; //Set this parameter to TRUE to transfer only those particles that do not meet all the criteria.
+ int rejectBorder; //Set this element to TRUE to reject border particles.
+ int connectivity8; //Set this parameter to TRUE to use connectivity-8 to determine whether particles are touching.
+} ParticleFilterOptions;
+
+typedef struct StraightEdgeReport2_struct {
+ StraightEdge* straightEdges; //Contains an array of found straight edges.
+ unsigned int numStraightEdges; //Indicates the number of straight edges found.
+ SearchLineInfo* searchLines; //Contains an array of all search lines used in the detection.
+ unsigned int numSearchLines; //The number of search lines used in the edge detection.
+} StraightEdgeReport2;
+
+typedef struct StraightEdgeOptions_struct {
+ unsigned int numLines; //Specifies the number of straight edges to find.
+ StraightEdgeSearchMode searchMode; //Specifies the method used to find the straight edge.
+ double minScore; //Specifies the minimum score of a detected straight edge.
+ double maxScore; //Specifies the maximum score of a detected edge.
+ double orientation; //Specifies the angle at which the straight edge is expected to be found.
+ double angleRange; //Specifies the +/- range around the orientation within which the straight edge is expected to be found.
+ double angleTolerance; //Specifies the expected angular accuracy of the straight edge.
+ unsigned int stepSize; //Specifies the gap in pixels between the search lines used with the rake-based methods.
+ double minSignalToNoiseRatio; //Specifies the minimum signal to noise ratio (SNR) of the edge points used to fit the straight edge.
+ double minCoverage; //Specifies the minimum number of points as a percentage of the number of search lines that need to be included in the detected straight edge.
+ unsigned int houghIterations; //Specifies the number of iterations used in the Hough-based method.
+} StraightEdgeOptions;
+
+typedef struct StraightEdge_struct {
+ LineFloat straightEdgeCoordinates; //End points of the detected straight edge in pixel coordinates.
+ LineFloat calibratedStraightEdgeCoordinates; //End points of the detected straight edge in real-world coordinates.
+ double angle; //Angle of the found edge using the pixel coordinates.
+ double calibratedAngle; //Angle of the found edge using the real-world coordinates.
+ double score; //Describes the score of the detected edge.
+ double straightness; //The straightness value of the detected straight edge.
+ double averageSignalToNoiseRatio; //Describes the average signal to noise ratio (SNR) of the detected edge.
+ int calibrationValid; //Indicates if the calibration data for the straight edge is valid.
+ EdgeInfo* usedEdges; //An array of edges that were used to determine this straight line.
+ unsigned int numUsedEdges; //Indicates the number of edges in the usedEdges array.
+} StraightEdge;
+
+typedef struct QRCodeSearchOptions_struct {
+ QRRotationMode rotationMode; //Specifies the amount of QR code rotation the function should allow for.
+ unsigned int skipLocation; //If set to TRUE, specifies that the function should assume that the QR code occupies the entire image (or the entire search region).
+ unsigned int edgeThreshold; //The strength of the weakest edge the function uses to find the coarse location of the QR code in the image.
+ QRDemodulationMode demodulationMode; //The demodulation mode the function uses to locate the QR code.
+ QRCellSampleSize cellSampleSize; //The cell sample size the function uses to locate the QR code.
+ QRCellFilterMode cellFilterMode; //The cell filter mode the function uses to locate the QR code.
+ unsigned int skewDegreesAllowed; //Specifies the amount of skew in the QR code the function should allow for.
+} QRCodeSearchOptions;
+
+typedef struct QRCodeSizeOptions_struct {
+ unsigned int minSize; //Specifies the minimum size (in pixels) of the QR code in the image.
+ unsigned int maxSize; //Specifies the maximum size (in pixels) of the QR code in the image.
+} QRCodeSizeOptions;
+
+typedef struct QRCodeDescriptionOptions_struct {
+ QRDimensions dimensions; //The number of rows and columns that are populated for the QR code, measured in cells.
+ QRPolarities polarity; //The polarity of the QR code.
+ QRMirrorMode mirror; //This element is TRUE if the QR code appears mirrored in the image and FALSE if the QR code appears normally in the image.
+ QRModelType modelType; //This option allows you to specify the type of QR code.
+} QRCodeDescriptionOptions;
+
+typedef struct QRCodeReport_struct {
+ unsigned int found; //This element is TRUE if the function located and decoded a QR code and FALSE if the function failed to locate and decode a QR code.
+ unsigned char* data; //The data encoded in the QR code.
+ unsigned int dataLength; //The length of the data array.
+ PointFloat boundingBox[4]; //An array of four points describing the rectangle surrounding the QR code.
+ QRCodeDataToken* tokenizedData; //Contains the data tokenized in exactly the way it was encoded in the code.
+ unsigned int sizeOfTokenizedData; //Size of the tokenized data.
+ unsigned int numErrorsCorrected; //The number of errors the function corrected when decoding the QR code.
+ unsigned int dimensions; //The number of rows and columns that are populated for the QR code, measured in cells.
+ unsigned int version; //The version of the QR code.
+ QRModelType modelType; //This option allows you to specify what type of QR code this is.
+ QRStreamMode streamMode; //The format of the data encoded in the stream.
+ QRPolarities matrixPolarity; //The polarity of the QR code.
+ unsigned int mirrored; //This element is TRUE if the QR code appears mirrored in the image and FALSE if the QR code appears normally in the image.
+ unsigned int positionInAppendStream; //Indicates what position the QR code is in with respect to the stream of data in all codes.
+ unsigned int sizeOfAppendStream; //Specifies how many QR codes are part of a larger array of codes.
+ int firstEAN128ApplicationID; //The first EAN-128 Application ID encountered in the stream.
+ int firstECIDesignator; //The first Regional Language Designator encountered in the stream.
+ unsigned int appendStreamIdentifier; //Specifies what stream the QR code is in relation to when the code is part of a larger array of codes.
+ unsigned int minimumEdgeStrength; //The strength of the weakest edge the function used to find the coarse location of the QR code in the image.
+ QRDemodulationMode demodulationMode; //The demodulation mode the function used to locate the QR code.
+ QRCellSampleSize cellSampleSize; //The cell sample size the function used to locate the QR code.
+ QRCellFilterMode cellFilterMode; //The cell filter mode the function used to locate the QR code.
+} QRCodeReport;
+
+typedef struct AIMGradeReport_struct {
+ AIMGrade overallGrade; //The overall letter grade, which is equal to the lowest of the other five letter grades.
+ AIMGrade decodingGrade; //The letter grade assigned to a Data Matrix barcode based on the success of the function in decoding the Data Matrix barcode.
+ AIMGrade symbolContrastGrade; //The letter grade assigned to a Data Matrix barcode based on the symbol contrast raw score.
+ float symbolContrast; //The symbol contrast raw score representing the percentage difference between the mean of the reflectance of the darkest 10 percent and lightest 10 percent of the Data Matrix barcode.
+ AIMGrade printGrowthGrade; //The print growth letter grade for the Data Matrix barcode.
+ float printGrowth; //The print growth raw score for the barcode, which is based on the extent to which dark or light markings appropriately fill their module boundaries.
+ AIMGrade axialNonuniformityGrade; //The axial nonuniformity grade for the Data Matrix barcode.
+ float axialNonuniformity; //The axial nonuniformity raw score for the barcode, which is based on how much the sampling point spacing differs from one axis to another.
+ AIMGrade unusedErrorCorrectionGrade; //The unused error correction letter grade for the Data Matrix barcode.
+ float unusedErrorCorrection; //The unused error correction raw score for the Data Matrix barcode, which is based on the extent to which regional or spot damage in the Data Matrix barcode has eroded the reading safety margin provided by the error correction.
+} AIMGradeReport;
+
+typedef struct DataMatrixSizeOptions_struct {
+ unsigned int minSize; //Specifies the minimum size (in pixels) of the Data Matrix barcode in the image.
+ unsigned int maxSize; //Specifies the maximum size (in pixels) of the Data Matrix barcode in the image.
+ unsigned int quietZoneWidth; //Specifies the expected minimum size of the quiet zone, in pixels.
+} DataMatrixSizeOptions;
+
+typedef struct DataMatrixDescriptionOptions_struct {
+ float aspectRatio; //Specifies the ratio of the width of each Data Matrix barcode cell (in pixels) to the height of the Data Matrix barcode (in pixels).
+ unsigned int rows; //Specifies the number of rows in the Data Matrix barcode.
+ unsigned int columns; //Specifies the number of columns in the Data Matrix barcode.
+ int rectangle; //Set this element to TRUE to specify that the Data Matrix barcode is rectangular.
+ DataMatrixECC ecc; //Specifies the ECC used for this Data Matrix barcode.
+ DataMatrixPolarity polarity; //Specifies the data-to-background contrast for the Data Matrix barcode.
+ DataMatrixCellFillMode cellFill; //Specifies the fill percentage for a cell of the Data Matrix barcode that is in the "ON" state.
+ float minBorderIntegrity; //Specifies the minimum percentage of the border (locator pattern and timing pattern) the function should expect in the Data Matrix barcode.
+ DataMatrixMirrorMode mirrorMode; //Specifies if the Data Matrix barcode appears normally in the image or if the barcode appears mirrored in the image.
+} DataMatrixDescriptionOptions;
+
+typedef struct DataMatrixSearchOptions_struct {
+ DataMatrixRotationMode rotationMode; //Specifies the amount of Data Matrix barcode rotation the function should allow for.
+ int skipLocation; //If set to TRUE, specifies that the function should assume that the Data Matrix barcode occupies the entire image (or the entire search region).
+ unsigned int edgeThreshold; //Specifies the minimum contrast a pixel must have in order to be considered part of a matrix cell edge.
+ DataMatrixDemodulationMode demodulationMode; //Specifies the mode the function should use to demodulate (determine which cells are on and which cells are off) the Data Matrix barcode.
+ DataMatrixCellSampleSize cellSampleSize; //Specifies the sample size, in pixels, the function should take to determine if each cell is on or off.
+ DataMatrixCellFilterMode cellFilterMode; //Specifies the mode the function uses to determine the pixel value for each cell.
+ unsigned int skewDegreesAllowed; //Specifies the amount of skew in the Data Matrix barcode the function should allow for.
+ unsigned int maxIterations; //Specifies the maximum number of iterations before the function stops looking for the Data Matrix barcode.
+ unsigned int initialSearchVectorWidth; //Specifies the number of pixels the function should average together to determine the location of an edge.
+} DataMatrixSearchOptions;
+
+typedef struct DataMatrixReport_struct {
+ int found; //This element is TRUE if the function located and decoded a Data Matrix barcode and FALSE if the function failed to locate and decode a Data Matrix barcode.
+ int binary; //This element is TRUE if the Data Matrix barcode contains binary data and FALSE if the Data Matrix barcode contains text data.
+ unsigned char* data; //The data encoded in the Data Matrix barcode.
+ unsigned int dataLength; //The length of the data array.
+ PointFloat boundingBox[4]; //An array of four points describing the rectangle surrounding the Data Matrix barcode.
+ unsigned int numErrorsCorrected; //The number of errors the function corrected when decoding the Data Matrix barcode.
+ unsigned int numErasuresCorrected; //The number of erasures the function corrected when decoding the Data Matrix barcode.
+ float aspectRatio; //Specifies the aspect ratio of the Data Matrix barcode in the image, which equals the ratio of the width of a Data Matrix barcode cell (in pixels) to the height of a Data Matrix barcode cell (in pixels).
+ unsigned int rows; //The number of rows in the Data Matrix barcode.
+ unsigned int columns; //The number of columns in the Data Matrix barcode.
+ DataMatrixECC ecc; //The Error Correction Code (ECC) used by the Data Matrix barcode.
+ DataMatrixPolarity polarity; //The polarity of the Data Matrix barcode.
+ DataMatrixCellFillMode cellFill; //The cell fill percentage of the Data Matrix barcode.
+ float borderIntegrity; //The percentage of the Data Matrix barcode border that appears correctly in the image.
+ int mirrored; //This element is TRUE if the Data Matrix barcode appears mirrored in the image and FALSE if the Data Matrix barcode appears normally in the image.
+ unsigned int minimumEdgeStrength; //The strength of the weakest edge the function used to find the coarse location of the Data Matrix barcode in the image.
+ DataMatrixDemodulationMode demodulationMode; //The demodulation mode the function used to locate the Data Matrix barcode.
+ DataMatrixCellSampleSize cellSampleSize; //The cell sample size the function used to locate the Data Matrix barcode.
+ DataMatrixCellFilterMode cellFilterMode; //The cell filter mode the function used to locate the Data Matrix barcode.
+ unsigned int iterations; //The number of iterations the function took in attempting to locate the Data Matrix barcode.
+} DataMatrixReport;
+
+typedef struct JPEG2000FileAdvancedOptions_struct {
+ WaveletTransformMode waveletMode; //Determines which wavelet transform to use when writing the file.
+ int useMultiComponentTransform; //Set this parameter to TRUE to use an additional transform on RGB images.
+ unsigned int maxWaveletTransformLevel; //Specifies the maximum allowed level of wavelet transform.
+ float quantizationStepSize; //Specifies the absolute base quantization step size for derived quantization mode.
+} JPEG2000FileAdvancedOptions;
+
+typedef struct MatchGeometricPatternAdvancedOptions2_struct {
+ int minFeaturesUsed; //Specifies the minimum number of features the function uses when matching.
+ int maxFeaturesUsed; //Specifies the maximum number of features the function uses when matching.
+ int subpixelIterations; //Specifies the maximum number of incremental improvements used to refine matches with subpixel information.
+ double subpixelTolerance; //Specifies the maximum amount of change, in pixels, between consecutive incremental improvements in the match position before the function stops refining the match position.
+ int initialMatchListLength; //Specifies the maximum size of the match list.
+ float matchTemplateCurveScore; //Set this element to TRUE to specify that the function should calculate the match curve to template curve score and return it for each match result.
+ int correlationScore; //Set this element to TRUE to specify that the function should calculate the correlation score and return it for each match result.
+ double minMatchSeparationDistance; //Specifies the minimum separation distance, in pixels, between the origins of two matches that have unique positions.
+ double minMatchSeparationAngle; //Specifies the minimum angular difference, in degrees, between two matches that have unique angles.
+ double minMatchSeparationScale; //Specifies the minimum difference in scale, expressed as a percentage, between two matches that have unique scales.
+ double maxMatchOverlap; //Specifies the maximum amount of overlap, expressed as a percentage, allowed between the bounding rectangles of two unique matches.
+ int coarseResult; //Specifies whether you want the function to spend less time accurately estimating the location of a match.
+ int smoothContours; //Set this element to TRUE to specify smoothing be done on the contours of the inspection image before feature extraction.
+ int enableCalibrationSupport; //Set this element to TRUE to specify the algorithm treat the inspection image as a calibrated image.
+} MatchGeometricPatternAdvancedOptions2;
+
+typedef struct InspectionAlignment_struct {
+ PointFloat position; //The location of the center of the golden template in the image under inspection.
+ float rotation; //The rotation of the golden template in the image under inspection, in degrees.
+ float scale; //The percentage of the size of the area under inspection compared to the size of the golden template.
+} InspectionAlignment;
+
+typedef struct InspectionOptions_struct {
+ RegistrationMethod registrationMethod; //Specifies how the function registers the golden template and the target image.
+ NormalizationMethod normalizationMethod; //Specifies how the function normalizes the golden template to the target image.
+ int edgeThicknessToIgnore; //Specifies desired thickness of edges to be ignored.
+ float brightThreshold; //Specifies the threshold for areas where the target image is brighter than the golden template.
+ float darkThreshold; //Specifies the threshold for areas where the target image is darker than the golden template.
+ int binary; //Specifies whether the function should return a binary image giving the location of defects, or a grayscale image giving the intensity of defects.
+} InspectionOptions;
+
+typedef struct CharReport2_struct {
+ const char* character; //The character value.
+ PointFloat corner[4]; //An array of four points that describes the rectangle that surrounds the character.
+ int lowThreshold; //The minimum value of the threshold range used for this character.
+ int highThreshold; //The maximum value of the threshold range used for this character.
+ int classificationScore; //The degree to which the assigned character class represents the object better than the other character classes in the character set.
+ int verificationScore; //The similarity of the character and the reference character for the character class.
+ int verified; //This element is TRUE if a reference character was found for the character class and FALSE if a reference character was not found.
+} CharReport2;
+
+typedef struct CharInfo2_struct {
+ const char* charValue; //Retrieves the character value of the corresponding character in the character set.
+ const Image* charImage; //The image you used to train this character.
+ const Image* internalImage; //The internal representation that NI Vision uses to match objects to this character.
+ int isReferenceChar; //This element is TRUE if the character is the reference character for the character class.
+} CharInfo2;
+
+typedef struct ReadTextReport2_struct {
+ const char* readString; //The read string.
+ CharReport2* characterReport; //An array of reports describing the properties of each identified character.
+ int numCharacterReports; //The number of identified characters.
+} ReadTextReport2;
+
+typedef struct EllipseFeature_struct {
+ PointFloat position; //The location of the center of the ellipse.
+ double rotation; //The orientation of the semi-major axis of the ellipse with respect to the horizontal.
+ double minorRadius; //The length of the semi-minor axis of the ellipse.
+ double majorRadius; //The length of the semi-major axis of the ellipse.
+} EllipseFeature;
+
+typedef struct CircleFeature_struct {
+ PointFloat position; //The location of the center of the circle.
+ double radius; //The radius of the circle.
+} CircleFeature;
+
+typedef struct ConstCurveFeature_struct {
+ PointFloat position; //The center of the circle that this constant curve lies upon.
+ double radius; //The radius of the circle that this constant curve lies upon.
+ double startAngle; //When traveling along the constant curve from one endpoint to the next in a counterclockwise manner, this is the angular component of the vector originating at the center of the constant curve and pointing towards the first endpoint of the constant curve.
+ double endAngle; //When traveling along the constant curve from one endpoint to the next in a counterclockwise manner, this is the angular component of the vector originating at the center of the constant curve and pointing towards the second endpoint of the constant curve.
+} ConstCurveFeature;
+
+typedef struct RectangleFeature_struct {
+ PointFloat position; //The center of the rectangle.
+ PointFloat corner[4]; //The four corners of the rectangle.
+ double rotation; //The orientation of the rectangle with respect to the horizontal.
+ double width; //The width of the rectangle.
+ double height; //The height of the rectangle.
+} RectangleFeature;
+
+typedef struct LegFeature_struct {
+ PointFloat position; //The location of the leg feature.
+ PointFloat corner[4]; //The four corners of the leg feature.
+ double rotation; //The orientation of the leg with respect to the horizontal.
+ double width; //The width of the leg.
+ double height; //The height of the leg.
+} LegFeature;
+
+typedef struct CornerFeature_struct {
+ PointFloat position; //The location of the corner feature.
+ double rotation; //The angular component of the vector bisecting the corner from position.
+ double enclosedAngle; //The measure of the enclosed angle of the corner.
+ int isVirtual;
+} CornerFeature;
+
+typedef struct LineFeature_struct {
+ PointFloat startPoint; //The starting point of the line.
+ PointFloat endPoint; //The ending point of the line.
+ double length; //The length of the line measured in pixels from the start point to the end point.
+ double rotation; //The orientation of the line with respect to the horizontal.
+} LineFeature;
+
+typedef struct ParallelLinePairFeature_struct {
+ PointFloat firstStartPoint; //The starting point of the first line of the pair.
+ PointFloat firstEndPoint; //The ending point of the first line of the pair.
+ PointFloat secondStartPoint; //The starting point of the second line of the pair.
+ PointFloat secondEndPoint; //The ending point of the second line of the pair.
+ double rotation; //The orientation of the feature with respect to the horizontal.
+ double distance; //The distance from the first line to the second line.
+} ParallelLinePairFeature;
+
+typedef struct PairOfParallelLinePairsFeature_struct {
+ ParallelLinePairFeature firstParallelLinePair; //The first parallel line pair.
+ ParallelLinePairFeature secondParallelLinePair; //The second parallel line pair.
+ double rotation; //The orientation of the feature with respect to the horizontal.
+ double distance; //The distance from the midline of the first parallel line pair to the midline of the second parallel line pair.
+} PairOfParallelLinePairsFeature;
+
+typedef union GeometricFeature_union {
+ CircleFeature* circle; //A pointer to a CircleFeature.
+ EllipseFeature* ellipse; //A pointer to an EllipseFeature.
+ ConstCurveFeature* constCurve; //A pointer to a ConstCurveFeature.
+ RectangleFeature* rectangle; //A pointer to a RectangleFeature.
+ LegFeature* leg; //A pointer to a LegFeature.
+ CornerFeature* corner; //A pointer to a CornerFeature.
+ ParallelLinePairFeature* parallelLinePair; //A pointer to a ParallelLinePairFeature.
+ PairOfParallelLinePairsFeature* pairOfParallelLinePairs; //A pointer to a PairOfParallelLinePairsFeature.
+ LineFeature* line; //A pointer to a LineFeature.
+ ClosedCurveFeature* closedCurve; //A pointer to a ClosedCurveFeature.
+} GeometricFeature;
+
+typedef struct FeatureData_struct {
+ FeatureType type; //An enumeration representing the type of the feature.
+ PointFloat* contourPoints; //A set of points describing the contour of the feature.
+ int numContourPoints; //The number of points in the contourPoints array.
+ GeometricFeature feature; //The feature data specific to this type of feature.
+} FeatureData;
+
+typedef struct GeometricPatternMatch2_struct {
+ PointFloat position; //The location of the origin of the template in the match.
+ float rotation; //The rotation of the match relative to the template image, in degrees.
+ float scale; //The size of the match relative to the size of the template image, expressed as a percentage.
+ float score; //The accuracy of the match.
+ PointFloat corner[4]; //An array of four points describing the rectangle surrounding the template image.
+ int inverse; //This element is TRUE if the match is an inverse of the template image.
+ float occlusion; //The percentage of the match that is occluded.
+ float templateMatchCurveScore; //The accuracy of the match obtained by comparing the template curves to the curves in the match region.
+ float matchTemplateCurveScore; //The accuracy of the match obtained by comparing the curves in the match region to the template curves.
+ float correlationScore; //The accuracy of the match obtained by comparing the template image to the match region using a correlation metric that compares the two regions as a function of their pixel values.
+ String255 label; //The label corresponding to this match when the match is returned by imaqMatchMultipleGeometricPatterns().
+ FeatureData* featureData; //The features used in this match.
+ int numFeatureData; //The size of the featureData array.
+ PointFloat calibratedPosition; //The location of the origin of the template in the match.
+ float calibratedRotation; //The rotation of the match relative to the template image, in degrees.
+ PointFloat calibratedCorner[4]; //An array of four points describing the rectangle surrounding the template image.
+} GeometricPatternMatch2;
+
+typedef struct ClosedCurveFeature_struct {
+ PointFloat position; //The center of the closed curve feature.
+ double arcLength; //The arc length of the closed curve feature.
+} ClosedCurveFeature;
+
+typedef struct LineMatch_struct {
+ PointFloat startPoint; //The starting point of the matched line.
+ PointFloat endPoint; //The ending point of the matched line.
+ double length; //The length of the line measured in pixels from the start point to the end point.
+ double rotation; //The orientation of the matched line.
+ double score; //The score of the matched line.
+} LineMatch;
+
+typedef struct LineDescriptor_struct {
+ double minLength; //Specifies the minimum length of a line the function will return.
+ double maxLength; //Specifies the maximum length of a line the function will return.
+} LineDescriptor;
+
+typedef struct RectangleDescriptor_struct {
+ double minWidth; //Specifies the minimum width of a rectangle the algorithm will return.
+ double maxWidth; //Specifies the maximum width of a rectangle the algorithm will return.
+ double minHeight; //Specifies the minimum height of a rectangle the algorithm will return.
+ double maxHeight; //Specifies the maximum height of a rectangle the algorithm will return.
+} RectangleDescriptor;
+
+typedef struct RectangleMatch_struct {
+ PointFloat corner[4]; //The corners of the matched rectangle.
+ double rotation; //The orientation of the matched rectangle.
+ double width; //The width of the matched rectangle.
+ double height; //The height of the matched rectangle.
+ double score; //The score of the matched rectangle.
+} RectangleMatch;
+
+typedef struct EllipseDescriptor_struct {
+ double minMajorRadius; //Specifies the minimum length of the semi-major axis of an ellipse the function will return.
+ double maxMajorRadius; //Specifies the maximum length of the semi-major axis of an ellipse the function will return.
+ double minMinorRadius; //Specifies the minimum length of the semi-minor axis of an ellipse the function will return.
+ double maxMinorRadius; //Specifies the maximum length of the semi-minor axis of an ellipse the function will return.
+} EllipseDescriptor;
+
+typedef struct EllipseMatch_struct {
+ PointFloat position; //The location of the center of the matched ellipse.
+ double rotation; //The orientation of the matched ellipse.
+ double majorRadius; //The length of the semi-major axis of the matched ellipse.
+ double minorRadius; //The length of the semi-minor axis of the matched ellipse.
+ double score; //The score of the matched ellipse.
+} EllipseMatch;
+
+typedef struct CircleMatch_struct {
+ PointFloat position; //The location of the center of the matched circle.
+ double radius; //The radius of the matched circle.
+ double score; //The score of the matched circle.
+} CircleMatch;
+
+typedef struct CircleDescriptor_struct {
+ double minRadius; //Specifies the minimum radius of a circle the function will return.
+ double maxRadius; //Specifies the maximum radius of a circle the function will return.
+} CircleDescriptor;
+
+typedef struct ShapeDetectionOptions_struct {
+ unsigned int mode; //Specifies the method used when looking for the shape in the image.
+ RangeFloat* angleRanges; //An array of angle ranges, in degrees, where each range specifies how much you expect the shape to be rotated in the image.
+ int numAngleRanges; //The size of the orientationRanges array.
+ RangeFloat scaleRange; //A range that specifies the sizes of the shapes you expect to be in the image, expressed as a ratio percentage representing the size of the pattern in the image divided by size of the original pattern multiplied by 100.
+ double minMatchScore;
+} ShapeDetectionOptions;
+
+typedef struct Curve_struct {
+ PointFloat* points; //The points on the curve.
+ unsigned int numPoints; //The number of points in the curve.
+ int closed; //This element is TRUE if the curve is closed and FALSE if the curve is open.
+ double curveLength; //The length of the curve.
+ double minEdgeStrength; //The lowest edge strength detected on the curve.
+ double maxEdgeStrength; //The highest edge strength detected on the curve.
+ double averageEdgeStrength; //The average of all edge strengths detected on the curve.
+} Curve;
+
+typedef struct CurveOptions_struct {
+ ExtractionMode extractionMode; //Specifies the method the function uses to identify curves in the image.
+ int threshold; //Specifies the minimum contrast a seed point must have in order to begin a curve.
+ EdgeFilterSize filterSize; //Specifies the width of the edge filter the function uses to identify curves in the image.
+ int minLength; //Specifies the length, in pixels, of the smallest curve the function will extract.
+ int rowStepSize; //Specifies the distance, in the y direction, between lines the function inspects for curve seed points.
+ int columnStepSize; //Specifies the distance, in the x direction, between columns the function inspects for curve seed points.
+ int maxEndPointGap; //Specifies the maximum gap, in pixels, between the endpoints of a curve that the function identifies as a closed curve.
+ int onlyClosed; //Set this element to TRUE to specify that the function should only identify closed curves in the image.
+ int subpixelAccuracy; //Set this element to TRUE to specify that the function identifies the location of curves with subpixel accuracy by interpolating between points to find the crossing of threshold.
+} CurveOptions;
+
+typedef struct Barcode2DInfo_struct {
+ Barcode2DType type; //The type of the 2D barcode.
+ int binary; //This element is TRUE if the 2D barcode contains binary data and FALSE if the 2D barcode contains text data.
+ unsigned char* data; //The data encoded in the 2D barcode.
+ unsigned int dataLength; //The length of the data array.
+ PointFloat boundingBox[4]; //An array of four points describing the rectangle surrounding the 2D barcode.
+ unsigned int numErrorsCorrected; //The number of errors the function corrected when decoding the 2D barcode.
+ unsigned int numErasuresCorrected; //The number of erasures the function corrected when decoding the 2D barcode.
+ unsigned int rows; //The number of rows in the 2D barcode.
+ unsigned int columns; //The number of columns in the 2D barcode.
+} Barcode2DInfo;
+
+typedef struct DataMatrixOptions_struct {
+ Barcode2DSearchMode searchMode; //Specifies the mode the function uses to search for barcodes.
+ Barcode2DContrast contrast; //Specifies the contrast of the barcodes that the function searches for.
+ Barcode2DCellShape cellShape; //Specifies the shape of the barcode data cells, which affects how the function decodes the barcode.
+ Barcode2DShape barcodeShape; //Specifies the shape of the barcodes that the function searches for.
+ DataMatrixSubtype subtype; //Specifies the Data Matrix subtypes of the barcodes that the function searches for.
+} DataMatrixOptions;
+
+typedef struct ClassifierAccuracyReport_struct {
+ int size; //The size of the arrays in this structure.
+ float accuracy; //The overall accuracy of the classifier, from 0 to 1000.
+ char** classNames; //The names of the classes of this classifier.
+ double* classAccuracy; //An array of size elements that contains accuracy information for each class.
+ double* classPredictiveValue; //An array containing size elements that contains the predictive values of each class.
+ int** classificationDistribution; //A two-dimensional array containing information about how the classifier classifies its samples.
+} ClassifierAccuracyReport;
+
+typedef struct NearestNeighborClassResult_struct {
+ char* className; //The name of the class.
+ float standardDeviation; //The standard deviation of the members of this class.
+ int count; //The number of samples in this class.
+} NearestNeighborClassResult;
+
+typedef struct NearestNeighborTrainingReport_struct {
+ float** classDistancesTable; //The confidence in the training.
+ NearestNeighborClassResult* allScores; //All classes and their scores.
+ int allScoresSize; //The number of entries in allScores.
+} NearestNeighborTrainingReport;
+
+typedef struct ParticleClassifierPreprocessingOptions_struct {
+ int manualThreshold; //Set this element to TRUE to specify the threshold range manually.
+ RangeFloat manualThresholdRange; //If a manual threshold is being done, the range of pixels to keep.
+ ThresholdMethod autoThresholdMethod; //If an automatic threshold is being done, the method used to calculate the threshold range.
+ RangeFloat limits; //The limits on the automatic threshold range.
+ ParticleType particleType; //Specifies what kind of particles to look for.
+ int rejectBorder; //Set this element to TRUE to reject border particles.
+ int numErosions; //The number of erosions to perform.
+} ParticleClassifierPreprocessingOptions;
+
+typedef struct ClassifierSampleInfo_struct {
+ char* className; //The name of the class this sample is in.
+ double* featureVector; //The feature vector of this sample, or NULL if this is not a custom classifier session.
+ int featureVectorSize; //The number of elements in the feature vector.
+ Image* thumbnail; //A thumbnail image of this sample, or NULL if no image was specified.
+} ClassifierSampleInfo;
+
+typedef struct ClassScore_struct {
+ char* className; //The name of the class.
+ float distance; //The distance from the item to this class.
+} ClassScore;
+
+typedef struct ClassifierReport_struct {
+ char* bestClassName; //The name of the best class for the sample.
+ float classificationScore; //The similarity of the sample and the two closest classes in the classifier.
+ float identificationScore; //The similarity of the sample and the assigned class.
+ ClassScore* allScores; //All classes and their scores.
+ int allScoresSize; //The number of entries in allScores.
+} ClassifierReport;
+
+typedef struct NearestNeighborOptions_struct {
+ NearestNeighborMethod method; //The method to use.
+ NearestNeighborMetric metric; //The metric to use.
+ int k; //The value of k, if the IMAQ_K_NEAREST_NEIGHBOR method is used.
+} NearestNeighborOptions;
+
+typedef struct ParticleClassifierOptions_struct {
+ float scaleDependence; //The relative importance of scale when classifying particles.
+ float mirrorDependence; //The relative importance of mirror symmetry when classifying particles.
+} ParticleClassifierOptions;
+
+typedef struct RGBU64Value_struct {
+ unsigned short B; //The blue value of the color.
+ unsigned short G; //The green value of the color.
+ unsigned short R; //The red value of the color.
+ unsigned short alpha; //The alpha value of the color, which represents extra information about a color image, such as gamma correction.
+} RGBU64Value;
+
+typedef struct GeometricPatternMatch_struct {
+ PointFloat position; //The location of the origin of the template in the match.
+ float rotation; //The rotation of the match relative to the template image, in degrees.
+ float scale; //The size of the match relative to the size of the template image, expressed as a percentage.
+ float score; //The accuracy of the match.
+ PointFloat corner[4]; //An array of four points describing the rectangle surrounding the template image.
+ int inverse; //This element is TRUE if the match is an inverse of the template image.
+ float occlusion; //The percentage of the match that is occluded.
+ float templateMatchCurveScore; //The accuracy of the match obtained by comparing the template curves to the curves in the match region.
+ float matchTemplateCurveScore; //The accuracy of the match obtained by comparing the curves in the match region to the template curves.
+ float correlationScore; //The accuracy of the match obtained by comparing the template image to the match region using a correlation metric that compares the two regions as a function of their pixel values.
+} GeometricPatternMatch;
+
+typedef struct MatchGeometricPatternAdvancedOptions_struct {
+ int minFeaturesUsed; //Specifies the minimum number of features the function uses when matching.
+ int maxFeaturesUsed; //Specifies the maximum number of features the function uses when matching.
+ int subpixelIterations; //Specifies the maximum number of incremental improvements used to refine matches with subpixel information.
+ double subpixelTolerance; //Specifies the maximum amount of change, in pixels, between consecutive incremental improvements in the match position before the function stops refining the match position.
+ int initialMatchListLength; //Specifies the maximum size of the match list.
+ int matchTemplateCurveScore; //Set this element to TRUE to specify that the function should calculate the match curve to template curve score and return it for each match result.
+ int correlationScore; //Set this element to TRUE to specify that the function should calculate the correlation score and return it for each match result.
+ double minMatchSeparationDistance; //Specifies the minimum separation distance, in pixels, between the origins of two matches that have unique positions.
+ double minMatchSeparationAngle; //Specifies the minimum angular difference, in degrees, between two matches that have unique angles.
+ double minMatchSeparationScale; //Specifies the minimum difference in scale, expressed as a percentage, between two matches that have unique scales.
+ double maxMatchOverlap; //Specifies the maximum amount of overlap, expressed as a percentage, allowed between the bounding rectangles of two unique matches.
+ int coarseResult; //Specifies whether you want the function to spend less time accurately estimating the location of a match.
+} MatchGeometricPatternAdvancedOptions;
+
+typedef struct MatchGeometricPatternOptions_struct {
+ unsigned int mode; //Specifies the method imaqMatchGeometricPattern() uses when looking for the pattern in the image.
+ int subpixelAccuracy; //Set this element to TRUE to specify that the function should calculate match locations with subpixel accuracy.
+ RangeFloat* angleRanges; //An array of angle ranges, in degrees, where each range specifies how much you expect the template to be rotated in the image.
+ int numAngleRanges; //Number of angle ranges in the angleRanges array.
+ RangeFloat scaleRange; //A range that specifies the sizes of the pattern you expect to be in the image, expressed as a ratio percentage representing the size of the pattern in the image divided by size of the original pattern multiplied by 100.
+ RangeFloat occlusionRange; //A range that specifies the percentage of the pattern you expect to be occluded in the image.
+ int numMatchesRequested; //Number of valid matches expected.
+ float minMatchScore; //The minimum score a match can have for the function to consider the match valid.
+} MatchGeometricPatternOptions;
+
+typedef struct LearnGeometricPatternAdvancedOptions_struct {
+ int minRectLength; //Specifies the minimum length for each side of a rectangular feature.
+ double minRectAspectRatio; //Specifies the minimum aspect ratio of a rectangular feature.
+ int minRadius; //Specifies the minimum radius for a circular feature.
+ int minLineLength; //Specifies the minimum length for a linear feature.
+ double minFeatureStrength; //Specifies the minimum strength for a feature.
+ int maxFeaturesUsed; //Specifies the maximum number of features the function uses when learning.
+ int maxPixelDistanceFromLine; //Specifies the maximum number of pixels between an edge pixel and a linear feature for the function to consider that edge pixel as part of the linear feature.
+} LearnGeometricPatternAdvancedOptions;
+
+typedef struct FitEllipseOptions_struct {
+ int rejectOutliers; //Whether to use every given point or only a subset of the points to fit the ellipse.
+ double minScore; //Specifies the required quality of the fitted ellipse.
+ double pixelRadius; //The acceptable distance, in pixels, that a point determined to belong to the ellipse can be from the circumference of the ellipse.
+ int maxIterations; //Specifies the number of refinement iterations you allow the function to perform on the initial subset of points.
+} FitEllipseOptions;
+
+typedef struct FitCircleOptions_struct {
+ int rejectOutliers; //Whether to use every given point or only a subset of the points to fit the circle.
+ double minScore; //Specifies the required quality of the fitted circle.
+ double pixelRadius; //The acceptable distance, in pixels, that a point determined to belong to the circle can be from the circumference of the circle.
+ int maxIterations; //Specifies the number of refinement iterations you allow the function to perform on the initial subset of points.
+} FitCircleOptions;
+
+typedef struct ConstructROIOptions2_struct {
+ int windowNumber; //The window number of the image window.
+ const char* windowTitle; //Specifies the message string that the function displays in the title bar of the window.
+ PaletteType type; //The palette type to use.
+ RGBValue* palette; //If type is IMAQ_PALETTE_USER, this array is the palette of colors to use with the window.
+ int numColors; //If type is IMAQ_PALETTE_USER, this element is the number of colors in the palette array.
+ unsigned int maxContours; //The maximum number of contours the user will be able to select.
+} ConstructROIOptions2;
+
+typedef struct HSLValue_struct {
+ unsigned char L; //The color luminance.
+ unsigned char S; //The color saturation.
+ unsigned char H; //The color hue.
+ unsigned char alpha; //The alpha value of the color, which represents extra information about a color image, such as gamma correction.
+} HSLValue;
+
+typedef struct HSVValue_struct {
+ unsigned char V; //The color value.
+ unsigned char S; //The color saturation.
+ unsigned char H; //The color hue.
+ unsigned char alpha; //The alpha value of the color, which represents extra information about a color image, such as gamma correction.
+} HSVValue;
+
+typedef struct HSIValue_struct {
+ unsigned char I; //The color intensity.
+ unsigned char S; //The color saturation.
+ unsigned char H; //The color hue.
+ unsigned char alpha; //The alpha value of the color, which represents extra information about a color image, such as gamma correction.
+} HSIValue;
+
+typedef struct CIELabValue_struct {
+ double b; //The yellow/blue information of the color.
+ double a; //The red/green information of the color.
+ double L; //The color lightness.
+ unsigned char alpha; //The alpha value of the color, which represents extra information about a color image, such as gamma correction.
+} CIELabValue;
+
+typedef struct CIEXYZValue_struct {
+ double Z; //The Z color information.
+ double Y; //The color luminance.
+ double X; //The X color information.
+ unsigned char alpha; //The alpha value of the color, which represents extra information about a color image, such as gamma correction.
+} CIEXYZValue;
+
+typedef union Color2_union {
+ RGBValue rgb; //The information needed to describe a color in the RGB (Red, Green, and Blue) color space.
+ HSLValue hsl; //The information needed to describe a color in the HSL (Hue, Saturation, and Luminance) color space.
+ HSVValue hsv; //The information needed to describe a color in the HSI (Hue, Saturation, and Value) color space.
+ HSIValue hsi; //The information needed to describe a color in the HSI (Hue, Saturation, and Intensity) color space.
+ CIELabValue cieLab; //The information needed to describe a color in the CIE L*a*b* (L, a, b) color space.
+ CIEXYZValue cieXYZ; //The information needed to describe a color in the CIE XYZ (X, Y, Z) color space.
+ int rawValue; //The integer value for the data in the color union.
+} Color2;
+
+typedef struct BestEllipse2_struct {
+ PointFloat center; //The coordinate location of the center of the ellipse.
+ PointFloat majorAxisStart; //The coordinate location of the start of the major axis of the ellipse.
+ PointFloat majorAxisEnd; //The coordinate location of the end of the major axis of the ellipse.
+ PointFloat minorAxisStart; //The coordinate location of the start of the minor axis of the ellipse.
+ PointFloat minorAxisEnd; //The coordinate location of the end of the minor axis of the ellipse.
+ double area; //The area of the ellipse.
+ double perimeter; //The length of the perimeter of the ellipse.
+ double error; //Represents the least square error of the fitted ellipse to the entire set of points.
+ int valid; //This element is TRUE if the function achieved the minimum score within the number of allowed refinement iterations and FALSE if the function did not achieve the minimum score.
+ int* pointsUsed; //An array of the indexes for the points array indicating which points the function used to fit the ellipse.
+ int numPointsUsed; //The number of points the function used to fit the ellipse.
+} BestEllipse2;
+
+typedef struct LearnPatternAdvancedOptions_struct {
+ LearnPatternAdvancedShiftOptions* shiftOptions; //Use this element to control the behavior of imaqLearnPattern2() during the shift-invariant learning phase.
+ LearnPatternAdvancedRotationOptions* rotationOptions; //Use this element to control the behavior of imaqLearnPattern2()during the rotation-invariant learning phase.
+} LearnPatternAdvancedOptions;
+
+typedef struct AVIInfo_struct {
+ unsigned int width; //The width of each frame.
+ unsigned int height; //The height of each frame.
+ ImageType imageType; //The type of images this AVI contains.
+ unsigned int numFrames; //The number of frames in the AVI.
+ unsigned int framesPerSecond; //The number of frames per second this AVI should be shown at.
+ char* filterName; //The name of the compression filter used to create this AVI.
+ int hasData; //Specifies whether this AVI has data attached to each frame or not.
+ unsigned int maxDataSize; //If this AVI has data, the maximum size of the data in each frame.
+} AVIInfo;
+
+typedef struct LearnPatternAdvancedShiftOptions_struct {
+ int initialStepSize; //The largest number of image pixels to shift the sample across the inspection image during the initial phase of shift-invariant matching.
+ int initialSampleSize; //Specifies the number of template pixels that you want to include in a sample for the initial phase of shift-invariant matching.
+ double initialSampleSizeFactor; //Specifies the size of the sample for the initial phase of shift-invariant matching as a percent of the template size, in pixels.
+ int finalSampleSize; //Specifies the number of template pixels you want to add to initialSampleSize for the final phase of shift-invariant matching.
+ double finalSampleSizeFactor; //Specifies the size of the sample for the final phase of shift-invariant matching as a percent of the edge points in the template, in pixels.
+ int subpixelSampleSize; //Specifies the number of template pixels that you want to include in a sample for the subpixel phase of shift-invariant matching.
+ double subpixelSampleSizeFactor; //Specifies the size of the sample for the subpixel phase of shift-invariant matching as a percent of the template size, in pixels.
+} LearnPatternAdvancedShiftOptions;
+
+typedef struct LearnPatternAdvancedRotationOptions_struct {
+ SearchStrategy searchStrategySupport; //Specifies the aggressiveness of the rotation search strategy available during the matching phase.
+ int initialStepSize; //The largest number of image pixels to shift the sample across the inspection image during the initial phase of matching.
+ int initialSampleSize; //Specifies the number of template pixels that you want to include in a sample for the initial phase of rotation-invariant matching.
+ double initialSampleSizeFactor; //Specifies the size of the sample for the initial phase of rotation-invariant matching as a percent of the template size, in pixels.
+ int initialAngularAccuracy; //Sets the angle accuracy, in degrees, to use during the initial phase of rotation-invariant matching.
+ int finalSampleSize; //Specifies the number of template pixels you want to add to initialSampleSize for the final phase of rotation-invariant matching.
+ double finalSampleSizeFactor; //Specifies the size of the sample for the final phase of rotation-invariant matching as a percent of the edge points in the template, in pixels.
+ int finalAngularAccuracy; //Sets the angle accuracy, in degrees, to use during the final phase of the rotation-invariant matching.
+ int subpixelSampleSize; //Specifies the number of template pixels that you want to include in a sample for the subpixel phase of rotation-invariant matching.
+ double subpixelSampleSizeFactor; //Specifies the size of the sample for the subpixel phase of rotation-invariant matching as a percent of the template size, in pixels.
+} LearnPatternAdvancedRotationOptions;
+
+typedef struct MatchPatternAdvancedOptions_struct {
+ int subpixelIterations; //Defines the maximum number of incremental improvements used to refine matching using subpixel information.
+ double subpixelTolerance; //Defines the maximum amount of change, in pixels, between consecutive incremental improvements in the match position that you want to trigger the end of the refinement process.
+ int initialMatchListLength; //Specifies the maximum size of the match list.
+ int matchListReductionFactor; //Specifies the reduction of the match list as matches are refined.
+ int initialStepSize; //Specifies the number of pixels to shift the sample across the inspection image during the initial phase of shift-invariant matching.
+ SearchStrategy searchStrategy; //Specifies the aggressiveness of the rotation search strategy.
+ int intermediateAngularAccuracy; //Specifies the accuracy to use during the intermediate phase of rotation-invariant matching.
+} MatchPatternAdvancedOptions;
+
+typedef struct ParticleFilterCriteria2_struct {
+ MeasurementType parameter; //The morphological measurement that the function uses for filtering.
+ float lower; //The lower bound of the criteria range.
+ float upper; //The upper bound of the criteria range.
+ int calibrated; //Set this element to TRUE to take calibrated measurements.
+ int exclude; //Set this element to TRUE to indicate that a match occurs when the measurement is outside the criteria range.
+} ParticleFilterCriteria2;
+
+typedef struct BestCircle2_struct {
+ PointFloat center; //The coordinate location of the center of the circle.
+ double radius; //The radius of the circle.
+ double area; //The area of the circle.
+ double perimeter; //The length of the perimeter of the circle.
+ double error; //Represents the least square error of the fitted circle to the entire set of points.
+ int valid; //This element is TRUE if the function achieved the minimum score within the number of allowed refinement iterations and FALSE if the function did not achieve the minimum score.
+ int* pointsUsed; //An array of the indexes for the points array indicating which points the function used to fit the circle.
+ int numPointsUsed; //The number of points the function used to fit the circle.
+} BestCircle2;
+
+typedef struct OCRSpacingOptions_struct {
+ int minCharSpacing; //The minimum number of pixels that must be between two characters for NI Vision to train or read the characters separately.
+ int minCharSize; //The minimum number of pixels required for an object to be a potentially identifiable character.
+ int maxCharSize; //The maximum number of pixels required for an object to be a potentially identifiable character.
+ int maxHorizontalElementSpacing; //The maximum horizontal spacing, in pixels, allowed between character elements to train or read the character elements as a single character.
+ int maxVerticalElementSpacing; //The maximum vertical element spacing in pixels.
+ int minBoundingRectWidth; //The minimum possible width, in pixels, for a character bounding rectangle.
+ int maxBoundingRectWidth; //The maximum possible width, in pixels, for a character bounding rectangle.
+ int minBoundingRectHeight; //The minimum possible height, in pixels, for a character bounding rectangle.
+ int maxBoundingRectHeight; //The maximum possible height, in pixels, for a character bounding rectangle.
+ int autoSplit; //Set this element to TRUE to automatically adjust the location of the character bounding rectangle when characters overlap vertically.
+} OCRSpacingOptions;
+
+typedef struct OCRProcessingOptions_struct {
+ ThresholdMode mode; //The thresholding mode.
+ int lowThreshold; //The low threshold value when you set mode to IMAQ_FIXED_RANGE.
+ int highThreshold; //The high threshold value when you set mode to IMAQ_FIXED_RANGE.
+ int blockCount; //The number of blocks for threshold calculation algorithms that require blocks.
+ int fastThreshold; //Set this element to TRUE to use a faster, less accurate threshold calculation algorithm.
+ int biModalCalculation; //Set this element to TRUE to calculate both the low and high threshold values when using the fast thresholding method.
+ int darkCharacters; //Set this element to TRUE to read or train dark characters on a light background.
+ int removeParticlesTouchingROI; //Set this element to TRUE to remove the particles touching the ROI.
+ int erosionCount; //The number of erosions to perform.
+} OCRProcessingOptions;
+
+typedef struct ReadTextOptions_struct {
+ String255 validChars[255]; //An array of strings that specifies the valid characters.
+ int numValidChars; //The number of strings in the validChars array that you have initialized.
+ char substitutionChar; //The character to substitute for objects that the function cannot match with any of the trained characters.
+ ReadStrategy readStrategy; //The read strategy, which determines how closely the function analyzes images in the reading process to match objects with trained characters.
+ int acceptanceLevel; //The minimum acceptance level at which an object is considered a trained character.
+ int aspectRatio; //The maximum aspect ratio variance percentage for valid characters.
+ ReadResolution readResolution; //The read resolution, which determines how much of the trained character data the function uses to match objects to trained characters.
+} ReadTextOptions;
+
+typedef struct CharInfo_struct {
+ const char* charValue; //Retrieves the character value of the corresponding character in the character set.
+ const Image* charImage; //The image you used to train this character.
+ const Image* internalImage; //The internal representation that NI Vision uses to match objects to this character.
+} CharInfo;
+
+#if !defined(USERINT_HEADER) && !defined(_CVI_RECT_DEFINED)
+typedef struct Rect_struct {
+ int top; //Location of the top edge of the rectangle.
+ int left; //Location of the left edge of the rectangle.
+ int height; //Height of the rectangle.
+ int width; //Width of the rectangle.
+} Rect;
+#define _CVI_RECT_DEFINED
+#endif
+
+typedef struct CharReport_struct {
+ const char* character; //The character value.
+ PointFloat corner[4]; //An array of four points that describes the rectangle that surrounds the character.
+ int reserved; //This element is reserved.
+ int lowThreshold; //The minimum value of the threshold range used for this character.
+ int highThreshold; //The maximum value of the threshold range used for this character.
+} CharReport;
+
+typedef struct ReadTextReport_struct {
+ const char* readString; //The read string.
+ const CharReport* characterReport; //An array of reports describing the properties of each identified character.
+ int numCharacterReports; //The number of identified characters.
+} ReadTextReport;
+
+#if !defined(USERINT_HEADER) && !defined(_CVI_POINT_DEFINED)
+typedef struct Point_struct {
+ int x; //The x-coordinate of the point.
+ int y; //The y-coordinate of the point.
+} Point;
+#define _CVI_POINT_DEFINED
+#endif
+
+typedef struct Annulus_struct {
+ Point center; //The coordinate location of the center of the annulus.
+ int innerRadius; //The internal radius of the annulus.
+ int outerRadius; //The external radius of the annulus.
+ double startAngle; //The start angle, in degrees, of the annulus.
+ double endAngle; //The end angle, in degrees, of the annulus.
+} Annulus;
+
+typedef struct EdgeLocationReport_struct {
+ PointFloat* edges; //The coordinate location of all edges detected by the search line.
+ int numEdges; //The number of points in the edges array.
+} EdgeLocationReport;
+
+typedef struct EdgeOptions_struct {
+ unsigned threshold; //Specifies the threshold value for the contrast of the edge.
+ unsigned width; //The number of pixels that the function averages to find the contrast at either side of the edge.
+ unsigned steepness; //The span, in pixels, of the slope of the edge projected along the path specified by the input points.
+ InterpolationMethod subpixelType; //The method for interpolating.
+ unsigned subpixelDivisions; //The number of samples the function obtains from a pixel.
+} EdgeOptions;
+
+typedef struct EdgeReport_struct {
+ float location; //The location of the edge from the first point in the points array.
+ float contrast; //The contrast at the edge.
+ PolarityType polarity; //The polarity of the edge.
+ float reserved; //This element is reserved.
+ PointFloat coordinate; //The coordinates of the edge.
+} EdgeReport;
+
+typedef struct ExtremeReport_struct {
+ double location; //The locations of the extreme.
+ double amplitude; //The amplitude of the extreme.
+ double secondDerivative; //The second derivative of the extreme.
+} ExtremeReport;
+
+typedef struct FitLineOptions_struct {
+ float minScore; //Specifies the required quality of the fitted line.
+ float pixelRadius; //Specifies the neighborhood pixel relationship for the initial subset of points being used.
+ int numRefinements; //Specifies the number of refinement iterations you allow the function to perform on the initial subset of points.
+} FitLineOptions;
+
+typedef struct DisplayMapping_struct {
+ MappingMethod method; //Describes the method for converting 16-bit pixels to 8-bit pixels.
+ int minimumValue; //When method is IMAQ_RANGE, minimumValue represents the value that is mapped to 0.
+ int maximumValue; //When method is IMAQ_RANGE, maximumValue represents the value that is mapped to 255.
+ int shiftCount; //When method is IMAQ_DOWNSHIFT, shiftCount represents the number of bits the function right-shifts the 16-bit pixel values.
+} DisplayMapping;
+
+typedef struct DetectExtremesOptions_struct {
+ double threshold; //Defines which extremes are too small.
+ int width; //Specifies the number of consecutive data points the function uses in the quadratic least-squares fit.
+} DetectExtremesOptions;
+
+typedef struct ImageInfo_struct {
+ CalibrationUnit imageUnit; //If you set calibration information with imaqSetSimpleCalibrationInfo(), imageUnit is the calibration unit.
+ float stepX; //If you set calibration information with imaqSetCalibrationInfo(), stepX is the distance in the calibration unit between two pixels in the x direction.
+ float stepY; //If you set calibration information with imaqSetCalibrationInfo(), stepY is the distance in the calibration unit between two pixels in the y direction.
+ ImageType imageType; //The type of the image.
+ int xRes; //The number of columns in the image.
+ int yRes; //The number of rows in the image.
+ int xOffset; //If you set mask offset information with imaqSetMaskOffset(), xOffset is the offset of the mask origin in the x direction.
+ int yOffset; //If you set mask offset information with imaqSetMaskOffset(), yOffset is the offset of the mask origin in the y direction.
+ int border; //The number of border pixels around the image.
+ int pixelsPerLine; //The number of pixels stored for each line of the image.
+ void* reserved0; //This element is reserved.
+ void* reserved1; //This element is reserved.
+ void* imageStart; //A pointer to pixel (0,0).
+} ImageInfo;
+
+typedef struct LCDOptions_struct {
+ int litSegments; //Set this parameter to TRUE if the segments are brighter than the background.
+ float threshold; //Determines whether a segment is ON or OFF.
+ int sign; //Indicates whether the function must read the sign of the indicator.
+ int decimalPoint; //Determines whether to look for a decimal separator after each digit.
+} LCDOptions;
+
+typedef struct LCDReport_struct {
+ const char* text; //A string of the characters of the LCD.
+ LCDSegments* segmentInfo; //An array of LCDSegment structures describing which segments of each digit are on.
+ int numCharacters; //The number of characters that the function reads.
+ int reserved; //This element is reserved.
+} LCDReport;
+
+typedef struct LCDSegments_struct {
+ unsigned a:1; //True if the a segment is on.
+ unsigned b:1; //True if the b segment is on.
+ unsigned c:1; //True if the c segment is on.
+ unsigned d:1; //True if the d segment is on.
+ unsigned e:1; //True if the e segment is on.
+ unsigned f:1; //True if the f segment is on.
+ unsigned g:1; //True if the g segment is on.
+ unsigned reserved:25; //This element is reserved.
+} LCDSegments;
+
+typedef struct LearnCalibrationOptions_struct {
+ CalibrationMode mode; //Specifies the type of algorithm you want to use to reduce distortion in your image.
+ ScalingMethod method; //Defines the scaling method correction functions use to correct the image.
+ CalibrationROI roi; //Specifies the ROI correction functions use when correcting an image.
+ int learnMap; //Set this element to TRUE if you want the function to calculate and store an error map during the learning process.
+ int learnTable; //Set this element to TRUE if you want the function to calculate and store the correction table.
+} LearnCalibrationOptions;
+
+typedef struct LearnColorPatternOptions_struct {
+ LearningMode learnMode; //Specifies the invariance mode the function uses when learning the pattern.
+ ImageFeatureMode featureMode; //Specifies the features the function uses when learning the color pattern.
+ int threshold; //Specifies the saturation threshold the function uses to distinguish between two colors that have the same hue values.
+ ColorIgnoreMode ignoreMode; //Specifies whether the function excludes certain colors from the color features of the template image.
+ ColorInformation* colorsToIgnore; //An array of ColorInformation structures providing a set of colors to exclude from the color features of the template image.
+ int numColorsToIgnore; //The number of ColorInformation structures in the colorsToIgnore array.
+} LearnColorPatternOptions;
+
+typedef struct Line_struct {
+ Point start; //The coordinate location of the start of the line.
+ Point end; //The coordinate location of the end of the line.
+} Line;
+
+typedef struct LinearAverages_struct {
+ float* columnAverages; //An array containing the mean pixel value of each column.
+ int columnCount; //The number of elements in the columnAverages array.
+ float* rowAverages; //An array containing the mean pixel value of each row.
+ int rowCount; //The number of elements in the rowAverages array.
+ float* risingDiagAverages; //An array containing the mean pixel value of each diagonal running from the lower left to the upper right of the inspected area of the image.
+ int risingDiagCount; //The number of elements in the risingDiagAverages array.
+ float* fallingDiagAverages; //An array containing the mean pixel value of each diagonal running from the upper left to the lower right of the inspected area of the image.
+ int fallingDiagCount; //The number of elements in the fallingDiagAverages array.
+} LinearAverages;
+
+typedef struct LineProfile_struct {
+ float* profileData; //An array containing the value of each pixel in the line.
+ Rect boundingBox; //The bounding rectangle of the line.
+ float min; //The smallest pixel value in the line profile.
+ float max; //The largest pixel value in the line profile.
+ float mean; //The mean value of the pixels in the line profile.
+ float stdDev; //The standard deviation of the line profile.
+ int dataCount; //The size of the profileData array.
+} LineProfile;
+
+typedef struct MatchColorPatternOptions_struct {
+ MatchingMode matchMode; //Specifies the method to use when looking for the color pattern in the image.
+ ImageFeatureMode featureMode; //Specifies the features to use when looking for the color pattern in the image.
+ int minContrast; //Specifies the minimum contrast expected in the image.
+ int subpixelAccuracy; //Set this parameter to TRUE to return areas in the image that match the pattern area with subpixel accuracy.
+ RotationAngleRange* angleRanges; //An array of angle ranges, in degrees, where each range specifies how much you expect the pattern to be rotated in the image.
+ int numRanges; //Number of angle ranges in the angleRanges array.
+ double colorWeight; //Determines the percent contribution of the color score to the final color pattern matching score.
+ ColorSensitivity sensitivity; //Specifies the sensitivity of the color information in the image.
+ SearchStrategy strategy; //Specifies how the color features of the image are used during the search phase.
+ int numMatchesRequested; //Number of valid matches expected.
+ float minMatchScore; //The minimum score a match can have for the function to consider the match valid.
+} MatchColorPatternOptions;
+
+typedef struct HistogramReport_struct {
+ int* histogram; //An array describing the number of pixels that fell into each class.
+ int histogramCount; //The number of elements in the histogram array.
+ float min; //The smallest pixel value that the function classified.
+ float max; //The largest pixel value that the function classified.
+ float start; //The smallest pixel value that fell into the first class.
+ float width; //The size of each class.
+ float mean; //The mean value of the pixels that the function classified.
+ float stdDev; //The standard deviation of the pixels that the function classified.
+ int numPixels; //The number of pixels that the function classified.
+} HistogramReport;
+
+typedef struct ArcInfo_struct {
+ Rect boundingBox; //The coordinate location of the bounding box of the arc.
+ double startAngle; //The counterclockwise angle from the x-axis in degrees to the start of the arc.
+ double endAngle; //The counterclockwise angle from the x-axis in degrees to the end of the arc.
+} ArcInfo;
+
+typedef struct AxisReport_struct {
+ PointFloat origin; //The origin of the coordinate system, which is the intersection of the two axes of the coordinate system.
+ PointFloat mainAxisEnd; //The end of the main axis, which is the result of the computation of the intersection of the main axis with the rectangular search area.
+ PointFloat secondaryAxisEnd; //The end of the secondary axis, which is the result of the computation of the intersection of the secondary axis with the rectangular search area.
+} AxisReport;
+
+typedef struct BarcodeInfo_struct {
+ const char* outputString; //A string containing the decoded barcode data.
+ int size; //The size of the output string.
+ char outputChar1; //The contents of this character depend on the barcode type.
+ char outputChar2; //The contents of this character depend on the barcode type.
+ double confidenceLevel; //A quality measure of the decoded barcode ranging from 0 to 100, with 100 being the best.
+ BarcodeType type; //The type of barcode.
+} BarcodeInfo;
+
+typedef struct BCGOptions_struct {
+ float brightness; //Adjusts the brightness of the image.
+ float contrast; //Adjusts the contrast of the image.
+ float gamma; //Performs gamma correction.
+} BCGOptions;
+
+typedef struct BestCircle_struct {
+ PointFloat center; //The coordinate location of the center of the circle.
+ double radius; //The radius of the circle.
+ double area; //The area of the circle.
+ double perimeter; //The length of the perimeter of the circle.
+ double error; //Represents the least square error of the fitted circle to the entire set of points.
+} BestCircle;
+
+typedef struct BestEllipse_struct {
+ PointFloat center; //The coordinate location of the center of the ellipse.
+ PointFloat majorAxisStart; //The coordinate location of the start of the major axis of the ellipse.
+ PointFloat majorAxisEnd; //The coordinate location of the end of the major axis of the ellipse.
+ PointFloat minorAxisStart; //The coordinate location of the start of the minor axis of the ellipse.
+ PointFloat minorAxisEnd; //The coordinate location of the end of the minor axis of the ellipse.
+ double area; //The area of the ellipse.
+ double perimeter; //The length of the perimeter of the ellipse.
+} BestEllipse;
+
+typedef struct BestLine_struct {
+ PointFloat start; //The coordinate location of the start of the line.
+ PointFloat end; //The coordinate location of the end of the line.
+ LineEquation equation; //Defines the three coefficients of the equation of the best fit line.
+ int valid; //This element is TRUE if the function achieved the minimum score within the number of allowed refinement iterations and FALSE if the function did not achieve the minimum score.
+ double error; //Represents the least square error of the fitted line to the entire set of points.
+ int* pointsUsed; //An array of the indexes for the points array indicating which points the function used to fit the line.
+ int numPointsUsed; //The number of points the function used to fit the line.
+} BestLine;
+
+typedef struct BrowserOptions_struct {
+ int width; //The width to make the browser.
+ int height; //The height to make the browser image.
+ int imagesPerLine; //The number of images to place on a single line.
+ RGBValue backgroundColor; //The background color of the browser.
+ int frameSize; //Specifies the number of pixels with which to border each thumbnail.
+ BrowserFrameStyle style; //The style for the frame around each thumbnail.
+ float ratio; //Specifies the width to height ratio of each thumbnail.
+ RGBValue focusColor; //The color to use to display focused cells.
+} BrowserOptions;
+
+typedef struct CoordinateSystem_struct {
+ PointFloat origin; //The origin of the coordinate system.
+ float angle; //The angle, in degrees, of the x-axis of the coordinate system relative to the image x-axis.
+ AxisOrientation axisOrientation; //The direction of the y-axis of the coordinate reference system.
+} CoordinateSystem;
+
+typedef struct CalibrationInfo_struct {
+ float* errorMap; //The error map for the calibration.
+ int mapColumns; //The number of columns in the error map.
+ int mapRows; //The number of rows in the error map.
+ ROI* userRoi; //Specifies the ROI the user provided when learning the calibration.
+ ROI* calibrationRoi; //Specifies the ROI that corresponds to the region of the image where the calibration information is accurate.
+ LearnCalibrationOptions options; //Specifies the calibration options the user provided when learning the calibration.
+ GridDescriptor grid; //Specifies the scaling constants for the image.
+ CoordinateSystem system; //Specifies the coordinate system for the real world coordinates.
+ RangeFloat range; //The range of the grayscale the function used to represent the circles in the grid image.
+ float quality; //The quality score of the learning process, which is a value between 0-1000.
+} CalibrationInfo;
+
+typedef struct CalibrationPoints_struct {
+ PointFloat* pixelCoordinates; //The array of pixel coordinates.
+ PointFloat* realWorldCoordinates; //The array of corresponding real-world coordinates.
+ int numCoordinates; //The number of coordinates in both of the arrays.
+} CalibrationPoints;
+
+typedef struct CaliperOptions_struct {
+ TwoEdgePolarityType polarity; //Specifies the edge polarity of the edge pairs.
+ float separation; //The distance between edge pairs.
+ float separationDeviation; //Sets the range around the separation value.
+} CaliperOptions;
+
+typedef struct CaliperReport_struct {
+ float edge1Contrast; //The contrast of the first edge.
+ PointFloat edge1Coord; //The coordinates of the first edge.
+ float edge2Contrast; //The contrast of the second edge.
+ PointFloat edge2Coord; //The coordinates of the second edge.
+ float separation; //The distance between the two edges.
+ float reserved; //This element is reserved.
+} CaliperReport;
+
+typedef struct DrawTextOptions_struct {
+ char fontName[32]; //The font name to use.
+ int fontSize; //The size of the font.
+ int bold; //Set this parameter to TRUE to bold text.
+ int italic; //Set this parameter to TRUE to italicize text.
+ int underline; //Set this parameter to TRUE to underline text.
+ int strikeout; //Set this parameter to TRUE to strikeout text.
+ TextAlignment textAlignment; //Sets the alignment of text.
+ FontColor fontColor; //Sets the font color.
+} DrawTextOptions;
+
+typedef struct CircleReport_struct {
+ Point center; //The coordinate point of the center of the circle.
+ int radius; //The radius of the circle, in pixels.
+ int area; //The area of the circle, in pixels.
+} CircleReport;
+
+typedef struct ClosedContour_struct {
+ Point* points; //The points that make up the closed contour.
+ int numPoints; //The number of points in the array.
+} ClosedContour;
+
+typedef struct ColorHistogramReport_struct {
+ HistogramReport plane1; //The histogram report of the first color plane.
+ HistogramReport plane2; //The histogram report of the second plane.
+ HistogramReport plane3; //The histogram report of the third plane.
+} ColorHistogramReport;
+
+typedef struct ColorInformation_struct {
+ int infoCount; //The size of the info array.
+ int saturation; //The saturation level the function uses to learn the color information.
+ double* info; //An array of color information that represents the color spectrum analysis of a region of an image in a compact form.
+} ColorInformation;
+
+typedef struct Complex_struct {
+ float r; //The real part of the value.
+ float i; //The imaginary part of the value.
+} Complex;
+
+typedef struct ConcentricRakeReport_struct {
+ ArcInfo* rakeArcs; //An array containing the location of each concentric arc line used for edge detection.
+ int numArcs; //The number of arc lines in the rakeArcs array.
+ PointFloat* firstEdges; //The coordinate location of all edges detected as first edges.
+ int numFirstEdges; //The number of points in the first edges array.
+ PointFloat* lastEdges; //The coordinate location of all edges detected as last edges.
+ int numLastEdges; //The number of points in the last edges array.
+ EdgeLocationReport* allEdges; //An array of reports describing the location of the edges located by each concentric rake arc line.
+ int* linesWithEdges; //An array of indices into the rakeArcs array indicating the concentric rake arc lines on which the function detected at least one edge.
+ int numLinesWithEdges; //The number of concentric rake arc lines along which the function detected edges.
+} ConcentricRakeReport;
+
+typedef struct ConstructROIOptions_struct {
+ int windowNumber; //The window number of the image window.
+ const char* windowTitle; //Specifies the message string that the function displays in the title bar of the window.
+ PaletteType type; //The palette type to use.
+ RGBValue* palette; //If type is IMAQ_PALETTE_USER, this array is the palette of colors to use with the window.
+ int numColors; //If type is IMAQ_PALETTE_USER, this element is the number of colors in the palette array.
+} ConstructROIOptions;
+
+typedef struct ContourInfo_struct {
+ ContourType type; //The contour type.
+ unsigned numPoints; //The number of points that make up the contour.
+ Point* points; //The points describing the contour.
+ RGBValue contourColor; //The contour color.
+} ContourInfo;
+
+typedef union ContourUnion_union {
+ Point* point; //Use this member when the contour is of type IMAQ_POINT.
+ Line* line; //Use this member when the contour is of type IMAQ_LINE.
+ Rect* rect; //Use this member when the contour is of type IMAQ_RECT.
+ Rect* ovalBoundingBox; //Use this member when the contour is of type IMAQ_OVAL.
+ ClosedContour* closedContour; //Use this member when the contour is of type IMAQ_CLOSED_CONTOUR.
+ OpenContour* openContour; //Use this member when the contour is of type IMAQ_OPEN_CONTOUR.
+ Annulus* annulus; //Use this member when the contour is of type IMAQ_ANNULUS.
+ RotatedRect* rotatedRect; //Use this member when the contour is of type IMAQ_ROTATED_RECT.
+} ContourUnion;
+
+typedef struct ContourInfo2_struct {
+ ContourType type; //The contour type.
+ RGBValue color; //The contour color.
+ ContourUnion structure; //The information necessary to describe the contour in coordinate space.
+} ContourInfo2;
+
+typedef struct ContourPoint_struct {
+ double x; //The x-coordinate value in the image.
+ double y; //The y-coordinate value in the image.
+ double curvature; //The change in slope at this edge point of the segment.
+ double xDisplacement; //The x displacement of the current edge pixel from a cubic spline fit of the current edge segment.
+ double yDisplacement; //The y displacement of the current edge pixel from a cubic spline fit of the current edge segment.
+} ContourPoint;
+
+typedef struct CoordinateTransform_struct {
+ Point initialOrigin; //The origin of the initial coordinate system.
+ float initialAngle; //The angle, in degrees, of the x-axis of the initial coordinate system relative to the image x-axis.
+ Point finalOrigin; //The origin of the final coordinate system.
+ float finalAngle; //The angle, in degrees, of the x-axis of the final coordinate system relative to the image x-axis.
+} CoordinateTransform;
+
+typedef struct CoordinateTransform2_struct {
+ CoordinateSystem referenceSystem; //Defines the coordinate system for input coordinates.
+ CoordinateSystem measurementSystem; //Defines the coordinate system in which the function should perform measurements.
+} CoordinateTransform2;
+
+typedef struct CannyOptions_struct {
+ float sigma; //The sigma of the Gaussian smoothing filter that the function applies to the image before edge detection.
+ float upperThreshold; //The upper fraction of pixel values in the image from which the function chooses a seed or starting point of an edge segment.
+ float lowerThreshold; //The function multiplies this value by upperThreshold to determine the lower threshold for all the pixels in an edge segment.
+ int windowSize; //The window size of the Gaussian filter that the function applies to the image.
+} CannyOptions;
+
+typedef struct Range_struct {
+ int minValue; //The minimum value of the range.
+ int maxValue; //The maximum value of the range.
+} Range;
+
+typedef struct UserPointSymbol_struct {
+ int cols; //Number of columns in the symbol.
+ int rows; //Number of rows in the symbol.
+ int* pixels; //The pixels of the symbol.
+} UserPointSymbol;
+
+typedef struct View3DOptions_struct {
+ int sizeReduction; //A divisor the function uses when determining the final height and width of the 3D image.
+ int maxHeight; //Defines the maximum height of a pixel from the image source drawn in 3D.
+ Direction3D direction; //Defines the 3D orientation.
+ float alpha; //Determines the angle between the horizontal and the baseline.
+ float beta; //Determines the angle between the horizontal and the second baseline.
+ int border; //Defines the border size.
+ int background; //Defines the background color.
+ Plane3D plane; //Indicates the view a function uses to show complex images.
+} View3DOptions;
+
+typedef struct MatchPatternOptions_struct {
+ MatchingMode mode; //Specifies the method to use when looking for the pattern in the image.
+ int minContrast; //Specifies the minimum contrast expected in the image.
+ int subpixelAccuracy; //Set this element to TRUE to return areas in the image that match the pattern area with subpixel accuracy.
+ RotationAngleRange* angleRanges; //An array of angle ranges, in degrees, where each range specifies how much you expect the pattern to be rotated in the image.
+ int numRanges; //Number of angle ranges in the angleRanges array.
+ int numMatchesRequested; //Number of valid matches expected.
+ int matchFactor; //Controls the number of potential matches that the function examines.
+ float minMatchScore; //The minimum score a match can have for the function to consider the match valid.
+} MatchPatternOptions;
+
+typedef struct TIFFFileOptions_struct {
+ int rowsPerStrip; //Indicates the number of rows that the function writes per strip.
+ PhotometricMode photoInterp; //Designates which photometric interpretation to use.
+ TIFFCompressionType compressionType; //Indicates the type of compression to use on the TIFF file.
+} TIFFFileOptions;
+
+typedef union Color_union {
+ RGBValue rgb; //The information needed to describe a color in the RGB (Red, Green, and Blue) color space.
+ HSLValue hsl; //The information needed to describe a color in the HSL (Hue, Saturation, and Luminance) color space.
+ HSVValue hsv; //The information needed to describe a color in the HSI (Hue, Saturation, and Value) color space.
+ HSIValue hsi; //The information needed to describe a color in the HSI (Hue, Saturation, and Intensity) color space.
+ int rawValue; //The integer value for the data in the color union.
+} Color;
+
+typedef union PixelValue_union {
+ float grayscale; //A grayscale pixel value.
+ RGBValue rgb; //A RGB pixel value.
+ HSLValue hsl; //A HSL pixel value.
+ Complex complex; //A complex pixel value.
+ RGBU64Value rgbu64; //An unsigned 64-bit RGB pixel value.
+} PixelValue;
+
+typedef struct OpenContour_struct {
+ Point* points; //The points that make up the open contour.
+ int numPoints; //The number of points in the array.
+} OpenContour;
+
+typedef struct OverlayTextOptions_struct {
+ const char* fontName; //The name of the font to use.
+ int fontSize; //The size of the font.
+ int bold; //Set this element to TRUE to bold the text.
+ int italic; //Set this element to TRUE to italicize the text.
+ int underline; //Set this element to TRUE to underline the text.
+ int strikeout; //Set this element to TRUE to strikeout the text.
+ TextAlignment horizontalTextAlignment; //Sets the alignment of the text.
+ VerticalTextAlignment verticalTextAlignment; //Sets the vertical alignment for the text.
+ RGBValue backgroundColor; //Sets the color for the text background pixels.
+ double angle; //The counterclockwise angle, in degrees, of the text relative to the x-axis.
+} OverlayTextOptions;
+
+typedef struct ParticleFilterCriteria_struct {
+ MeasurementValue parameter; //The morphological measurement that the function uses for filtering.
+ float lower; //The lower bound of the criteria range.
+ float upper; //The upper bound of the criteria range.
+ int exclude; //Set this element to TRUE to indicate that a match occurs when the value is outside the criteria range.
+} ParticleFilterCriteria;
+
+typedef struct ParticleReport_struct {
+ int area; //The number of pixels in the particle.
+ float calibratedArea; //The size of the particle, calibrated to the calibration information of the image.
+ float perimeter; //The length of the perimeter, calibrated to the calibration information of the image.
+ int numHoles; //The number of holes in the particle.
+ int areaOfHoles; //The total surface area, in pixels, of all the holes in a particle.
+ float perimeterOfHoles; //The length of the perimeter of all the holes in the particle calibrated to the calibration information of the image.
+ Rect boundingBox; //The smallest rectangle that encloses the particle.
+ float sigmaX; //The sum of the particle pixels on the x-axis.
+ float sigmaY; //The sum of the particle pixels on the y-axis.
+ float sigmaXX; //The sum of the particle pixels on the x-axis, squared.
+ float sigmaYY; //The sum of the particle pixels on the y-axis, squared.
+ float sigmaXY; //The sum of the particle pixels on the x-axis and y-axis.
+ int longestLength; //The length of the longest horizontal line segment.
+ Point longestPoint; //The location of the leftmost pixel of the longest segment in the particle.
+ int projectionX; //The length of the particle when projected onto the x-axis.
+ int projectionY; //The length of the particle when projected onto the y-axis.
+ int connect8; //This element is TRUE if the function used connectivity-8 to determine if particles are touching.
+} ParticleReport;
+
+typedef struct PatternMatch_struct {
+ PointFloat position; //The location of the center of the match.
+ float rotation; //The rotation of the match relative to the template image, in degrees.
+ float scale; //The size of the match relative to the size of the template image, expressed as a percentage.
+ float score; //The accuracy of the match.
+ PointFloat corner[4]; //An array of four points describing the rectangle surrounding the template image.
+} PatternMatch;
+
+typedef struct QuantifyData_struct {
+ float mean; //The mean value of the pixel values.
+ float stdDev; //The standard deviation of the pixel values.
+ float min; //The smallest pixel value.
+ float max; //The largest pixel value.
+ float calibratedArea; //The area, calibrated to the calibration information of the image.
+ int pixelArea; //The area, in number of pixels.
+ float relativeSize; //The proportion, expressed as a percentage, of the associated region relative to the whole image.
+} QuantifyData;
+
+typedef struct QuantifyReport_struct {
+ QuantifyData global; //Statistical data of the whole image.
+ QuantifyData* regions; //An array of QuantifyData structures containing statistical data of each region of the image.
+ int regionCount; //The number of regions.
+} QuantifyReport;
+
+typedef struct RakeOptions_struct {
+ int threshold; //Specifies the threshold value for the contrast of the edge.
+ int width; //The number of pixels that the function averages to find the contrast at either side of the edge.
+ int steepness; //The span, in pixels, of the slope of the edge projected along the path specified by the input points.
+ int subsamplingRatio; //Specifies the number of pixels that separate two consecutive search lines.
+ InterpolationMethod subpixelType; //The method for interpolating.
+ int subpixelDivisions; //The number of samples the function obtains from a pixel.
+} RakeOptions;
+
+typedef struct RakeReport_struct {
+ LineFloat* rakeLines; //The coordinate location of each of the rake lines used by the function.
+ int numRakeLines; //The number of lines in the rakeLines array.
+ PointFloat* firstEdges; //The coordinate location of all edges detected as first edges.
+ unsigned int numFirstEdges; //The number of points in the firstEdges array.
+ PointFloat* lastEdges; //The coordinate location of all edges detected as last edges.
+ unsigned int numLastEdges; //The number of points in the lastEdges array.
+ EdgeLocationReport* allEdges; //An array of reports describing the location of the edges located by each rake line.
+ int* linesWithEdges; //An array of indices into the rakeLines array indicating the rake lines on which the function detected at least one edge.
+ int numLinesWithEdges; //The number of rake lines along which the function detected edges.
+} RakeReport;
+
+typedef struct TransformReport_struct {
+ PointFloat* points; //An array of transformed coordinates.
+ int* validPoints; //An array of values that describe the validity of each of the coordinates according to the region of interest you calibrated using either imaqLearnCalibrationGrid() or imaqLearnCalibrationPoints().
+ int numPoints; //The length of both the points array and the validPoints array.
+} TransformReport;
+
+typedef struct ShapeReport_struct {
+ Rect coordinates; //The bounding rectangle of the object.
+ Point centroid; //The coordinate location of the centroid of the object.
+ int size; //The size, in pixels, of the object.
+ double score; //A value ranging between 1 and 1,000 that specifies how similar the object in the image is to the template.
+} ShapeReport;
+
+typedef struct MeterArc_struct {
+ PointFloat needleBase; //The coordinate location of the base of the meter needle.
+ PointFloat* arcCoordPoints; //An array of points describing the coordinate location of the meter arc.
+ int numOfArcCoordPoints; //The number of points in the arcCoordPoints array.
+ int needleColor; //This element is TRUE when the meter has a light-colored needle on a dark background.
+} MeterArc;
+
+typedef struct ThresholdData_struct {
+ float rangeMin; //The lower boundary of the range to keep.
+ float rangeMax; //The upper boundary of the range to keep.
+ float newValue; //If useNewValue is TRUE, newValue is the replacement value for pixels within the range.
+ int useNewValue; //If TRUE, the function sets pixel values within [rangeMin, rangeMax] to the value specified in newValue.
+} ThresholdData;
+
+typedef struct StructuringElement_struct {
+ int matrixCols; //Number of columns in the matrix.
+ int matrixRows; //Number of rows in the matrix.
+ int hexa; //Set this element to TRUE if you specify a hexagonal structuring element in kernel.
+ int* kernel; //The values of the structuring element.
+} StructuringElement;
+
+typedef struct SpokeReport_struct {
+ LineFloat* spokeLines; //The coordinate location of each of the spoke lines used by the function.
+ int numSpokeLines; //The number of lines in the spokeLines array.
+ PointFloat* firstEdges; //The coordinate location of all edges detected as first edges.
+ int numFirstEdges; //The number of points in the firstEdges array.
+ PointFloat* lastEdges; //The coordinate location of all edges detected as last edges.
+ int numLastEdges; //The number of points in the lastEdges array.
+ EdgeLocationReport* allEdges; //An array of reports describing the location of the edges located by each spoke line.
+ int* linesWithEdges; //An array of indices into the spokeLines array indicating the rake lines on which the function detected at least one edge.
+ int numLinesWithEdges; //The number of spoke lines along which the function detects edges.
+} SpokeReport;
+
+typedef struct SimpleEdgeOptions_struct {
+ LevelType type; //Determines how the function evaluates the threshold and hysteresis values.
+ int threshold; //The pixel value at which an edge occurs.
+ int hysteresis; //A value that helps determine edges in noisy images.
+ EdgeProcess process; //Determines which edges the function looks for.
+ int subpixel; //Set this element to TRUE to find edges with subpixel accuracy by interpolating between points to find the crossing of the given threshold.
+} SimpleEdgeOptions;
+
+typedef struct SelectParticleCriteria_struct {
+ MeasurementValue parameter; //The morphological measurement that the function uses for filtering.
+ float lower; //The lower boundary of the criteria range.
+ float upper; //The upper boundary of the criteria range.
+} SelectParticleCriteria;
+
+typedef struct SegmentInfo_struct {
+ int numberOfPoints; //The number of points in the segment.
+ int isOpen; //If TRUE, the contour is open.
+ double weight; //The significance of the edge in terms of the gray values that constitute the edge.
+ ContourPoint* points; //The points of the segment.
+} SegmentInfo;
+
+typedef struct RotationAngleRange_struct {
+ float lower; //The lowest amount of rotation, in degrees, a valid pattern can have.
+ float upper; //The highest amount of rotation, in degrees, a valid pattern can have.
+} RotationAngleRange;
+
+typedef struct RotatedRect_struct {
+ int top; //Location of the top edge of the rectangle before rotation.
+ int left; //Location of the left edge of the rectangle before rotation.
+ int height; //Height of the rectangle.
+ int width; //Width of the rectangle.
+ double angle; //The rotation, in degrees, of the rectangle.
+} RotatedRect;
+
+typedef struct ROIProfile_struct {
+ LineProfile report; //Quantifying information about the points along the edge of each contour in the ROI.
+ Point* pixels; //An array of the points along the edge of each contour in the ROI.
+} ROIProfile;
+
+typedef struct ToolWindowOptions_struct {
+ int showSelectionTool; //If TRUE, the selection tool becomes visible.
+ int showZoomTool; //If TRUE, the zoom tool becomes visible.
+ int showPointTool; //If TRUE, the point tool becomes visible.
+ int showLineTool; //If TRUE, the line tool becomes visible.
+ int showRectangleTool; //If TRUE, the rectangle tool becomes visible.
+ int showOvalTool; //If TRUE, the oval tool becomes visible.
+ int showPolygonTool; //If TRUE, the polygon tool becomes visible.
+ int showClosedFreehandTool; //If TRUE, the closed freehand tool becomes visible.
+ int showPolyLineTool; //If TRUE, the polyline tool becomes visible.
+ int showFreehandTool; //If TRUE, the freehand tool becomes visible.
+ int showAnnulusTool; //If TRUE, the annulus becomes visible.
+ int showRotatedRectangleTool; //If TRUE, the rotated rectangle tool becomes visible.
+ int showPanTool; //If TRUE, the pan tool becomes visible.
+ int showZoomOutTool; //If TRUE, the zoom out tool becomes visible.
+ int reserved2; //This element is reserved and should be set to FALSE.
+ int reserved3; //This element is reserved and should be set to FALSE.
+ int reserved4; //This element is reserved and should be set to FALSE.
+} ToolWindowOptions;
+
+typedef struct SpokeOptions_struct {
+ int threshold; //Specifies the threshold value for the contrast of the edge.
+ int width; //The number of pixels that the function averages to find the contrast at either side of the edge.
+ int steepness; //The span, in pixels, of the slope of the edge projected along the path specified by the input points.
+ double subsamplingRatio; //The angle, in degrees, between each radial search line in the spoke.
+ InterpolationMethod subpixelType; //The method for interpolating.
+ int subpixelDivisions; //The number of samples the function obtains from a pixel.
+} SpokeOptions;
+
+#if !defined __GNUC__ && !defined _M_X64
+#pragma pack(pop)
+#endif
+
+//============================================================================
+// Callback Function Type
+//============================================================================
+#ifndef __GNUC__
+typedef void (IMAQ_CALLBACK* EventCallback)(WindowEventType event, int windowNumber, Tool tool, Rect rect);
+#endif
+
+//============================================================================
+// Globals
+//============================================================================
+#ifndef __GNUC__
+#pragma const_seg("IMAQVisionColorConstants")
+#endif
+static const RGBValue IMAQ_RGB_TRANSPARENT = { 0, 0, 0, 1 };
+static const RGBValue IMAQ_RGB_RED = { 0, 0, 255, 0 };
+static const RGBValue IMAQ_RGB_BLUE = { 255, 0, 0, 0 };
+static const RGBValue IMAQ_RGB_GREEN = { 0, 255, 0, 0 };
+static const RGBValue IMAQ_RGB_YELLOW = { 0, 255, 255, 0 };
+static const RGBValue IMAQ_RGB_WHITE = { 255, 255, 255, 0 };
+static const RGBValue IMAQ_RGB_BLACK = { 0, 0, 0, 0 };
+#ifndef __GNUC__
+#pragma const_seg()
+#endif
+
+//============================================================================
+// Backwards Compatibility
+//============================================================================
+typedef ColorSensitivity ColorComplexity;
+#define IMAQ_COMPLEXITY_LOW IMAQ_SENSITIVITY_LOW
+#define IMAQ_COMPLEXITY_MED IMAQ_SENSITIVITY_MED
+#define IMAQ_COMPLEXITY_HIGH IMAQ_SENSITIVITY_HIGH
+#define ERR_INVALID_COLORCOMPLEXITY ERR_INVALID_COLORSENSITIVITY
+
+//============================================================================
+// Logical functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqAnd(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqAndConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqCompare(Image* dest, const Image* source, const Image* compareImage, ComparisonFunction compare);
+IMAQ_FUNC int IMAQ_STDCALL imaqCompareConstant(Image* dest, const Image* source, PixelValue value, ComparisonFunction compare);
+IMAQ_FUNC int IMAQ_STDCALL imaqLogicalDifference(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqLogicalDifferenceConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqNand(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqNandConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqNor(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqNorConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqOr(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqOrConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqXnor(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqXnorConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqXor(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqXorConstant(Image* dest, const Image* source, PixelValue value);
+
+//============================================================================
+// Particle Analysis functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCountParticles(Image* image, int connectivity8, int* numParticles);
+IMAQ_FUNC int IMAQ_STDCALL imaqMeasureParticle(Image* image, int particleNumber, int calibrated, MeasurementType measurement, double* value);
+IMAQ_FUNC MeasureParticlesReport* IMAQ_STDCALL imaqMeasureParticles(Image* image, MeasureParticlesCalibrationMode calibrationMode, const MeasurementType* measurements, size_t numMeasurements);
+IMAQ_FUNC int IMAQ_STDCALL imaqParticleFilter4(Image* dest, Image* source, const ParticleFilterCriteria2* criteria, int criteriaCount, const ParticleFilterOptions2* options, const ROI* roi, int* numParticles);
+
+//============================================================================
+// Morphology functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqConvexHull(Image* dest, Image* source, int connectivity8);
+IMAQ_FUNC int IMAQ_STDCALL imaqDanielssonDistance(Image* dest, Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqFillHoles(Image* dest, const Image* source, int connectivity8);
+IMAQ_FUNC CircleReport* IMAQ_STDCALL imaqFindCircles(Image* dest, Image* source, float minRadius, float maxRadius, int* numCircles);
+IMAQ_FUNC int IMAQ_STDCALL imaqLabel2(Image* dest, Image* source, int connectivity8, int* particleCount);
+IMAQ_FUNC int IMAQ_STDCALL imaqMorphology(Image* dest, Image* source, MorphologyMethod method, const StructuringElement* structuringElement);
+IMAQ_FUNC int IMAQ_STDCALL imaqRejectBorder(Image* dest, Image* source, int connectivity8);
+IMAQ_FUNC int IMAQ_STDCALL imaqSegmentation(Image* dest, Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqSeparation(Image* dest, Image* source, int erosions, const StructuringElement* structuringElement);
+IMAQ_FUNC int IMAQ_STDCALL imaqSimpleDistance(Image* dest, Image* source, const StructuringElement* structuringElement);
+IMAQ_FUNC int IMAQ_STDCALL imaqSizeFilter(Image* dest, Image* source, int connectivity8, int erosions, SizeType keepSize, const StructuringElement* structuringElement);
+IMAQ_FUNC int IMAQ_STDCALL imaqSkeleton(Image* dest, Image* source, SkeletonMethod method);
+
+
+//============================================================================
+// Acquisition functions
+//============================================================================
+IMAQ_FUNC Image* IMAQ_STDCALL imaqCopyFromRing(SESSION_ID sessionID, Image* image, int imageToCopy, int* imageNumber, Rect rect);
+IMAQ_FUNC Image* IMAQ_STDCALL imaqEasyAcquire(const char* interfaceName);
+IMAQ_FUNC Image* IMAQ_STDCALL imaqExtractFromRing(SESSION_ID sessionID, int imageToExtract, int* imageNumber);
+IMAQ_FUNC Image* IMAQ_STDCALL imaqGrab(SESSION_ID sessionID, Image* image, int immediate);
+IMAQ_FUNC int IMAQ_STDCALL imaqReleaseImage(SESSION_ID sessionID);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetupGrab(SESSION_ID sessionID, Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetupRing(SESSION_ID sessionID, Image** images, int numImages, int skipCount, Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetupSequence(SESSION_ID sessionID, Image** images, int numImages, int skipCount, Rect rect);
+IMAQ_FUNC Image* IMAQ_STDCALL imaqSnap(SESSION_ID sessionID, Image* image, Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqStartAcquisition(SESSION_ID sessionID);
+IMAQ_FUNC int IMAQ_STDCALL imaqStopAcquisition(SESSION_ID sessionID);
+
+//============================================================================
+// Arithmetic functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqAbsoluteDifference(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqAbsoluteDifferenceConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqAdd(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqAddConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqAverage(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqAverageConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqDivide2(Image* dest, const Image* sourceA, const Image* sourceB, RoundingMode roundingMode);
+IMAQ_FUNC int IMAQ_STDCALL imaqDivideConstant2(Image* dest, const Image* source, PixelValue value, RoundingMode roundingMode);
+IMAQ_FUNC int IMAQ_STDCALL imaqMax(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqMaxConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqMin(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqMinConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqModulo(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqModuloConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqMulDiv(Image* dest, const Image* sourceA, const Image* sourceB, float value);
+IMAQ_FUNC int IMAQ_STDCALL imaqMultiply(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqMultiplyConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqSubtract(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqSubtractConstant(Image* dest, const Image* source, PixelValue value);
+
+//============================================================================
+// Caliper functions
+//============================================================================
+IMAQ_FUNC CaliperReport* IMAQ_STDCALL imaqCaliperTool(const Image* image, const Point* points, int numPoints, const EdgeOptions* edgeOptions, const CaliperOptions* caliperOptions, int* numEdgePairs);
+IMAQ_FUNC ConcentricRakeReport2* IMAQ_STDCALL imaqConcentricRake2(Image* image, ROI* roi, ConcentricRakeDirection direction, EdgeProcess process, int stepSize, EdgeOptions2* edgeOptions);
+IMAQ_FUNC ExtremeReport* IMAQ_STDCALL imaqDetectExtremes(const double* pixels, int numPixels, DetectionMode mode, const DetectExtremesOptions* options, int* numExtremes);
+IMAQ_FUNC int IMAQ_STDCALL imaqDetectRotation(const Image* referenceImage, const Image* testImage, PointFloat referenceCenter, PointFloat testCenter, int radius, float precision, double* angle);
+IMAQ_FUNC EdgeReport2* IMAQ_STDCALL imaqEdgeTool4(Image* image, ROI* roi, EdgeProcess processType, EdgeOptions2* edgeOptions, const unsigned int reverseDirection);
+IMAQ_FUNC FindEdgeReport* IMAQ_STDCALL imaqFindEdge2(Image* image, const ROI* roi, const CoordinateSystem* baseSystem, const CoordinateSystem* newSystem, const FindEdgeOptions2* findEdgeOptions, const StraightEdgeOptions* straightEdgeOptions);
+IMAQ_FUNC int IMAQ_STDCALL imaqFindTransformRect2(Image* image, const ROI* roi, FindTransformMode mode, CoordinateSystem* baseSystem, CoordinateSystem* newSystem, const FindTransformRectOptions2* findTransformOptions, const StraightEdgeOptions* straightEdgeOptions, AxisReport* axisReport);
+IMAQ_FUNC int IMAQ_STDCALL imaqFindTransformRects2(Image* image, const ROI* primaryROI, const ROI* secondaryROI, FindTransformMode mode, CoordinateSystem* baseSystem, CoordinateSystem* newSystem, const FindTransformRectsOptions2* findTransformOptions, const StraightEdgeOptions* primaryStraightEdgeOptions, const StraightEdgeOptions* secondaryStraightEdgeOptions, AxisReport* axisReport);
+IMAQ_FUNC int IMAQ_STDCALL imaqLineGaugeTool2(const Image* image, Point start, Point end, LineGaugeMethod method, const EdgeOptions* edgeOptions, const CoordinateTransform2* transform, float* distance);
+IMAQ_FUNC RakeReport2* IMAQ_STDCALL imaqRake2(Image* image, ROI* roi, RakeDirection direction, EdgeProcess process, int stepSize, EdgeOptions2* edgeOptions);
+IMAQ_FUNC PointFloat* IMAQ_STDCALL imaqSimpleEdge(const Image* image, const Point* points, int numPoints, const SimpleEdgeOptions* options, int* numEdges);
+IMAQ_FUNC SpokeReport2* IMAQ_STDCALL imaqSpoke2(Image* image, ROI* roi, SpokeDirection direction, EdgeProcess process, int stepSize, EdgeOptions2* edgeOptions);
+IMAQ_FUNC StraightEdgeReport2* IMAQ_STDCALL imaqStraightEdge(const Image* image, const ROI* roi, SearchDirection searchDirection, const EdgeOptions2* edgeOptions, const StraightEdgeOptions* straightEdgeOptions);
+IMAQ_FUNC StraightEdgeReport2* IMAQ_STDCALL imaqStraightEdge2(const Image* image, const ROI* roi, SearchDirection searchDirection, const EdgeOptions2* edgeOptions, const StraightEdgeOptions* straightEdgeOptions, unsigned int optimizedMode);
+
+//============================================================================
+// Spatial Filters functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCannyEdgeFilter(Image* dest, const Image* source, const CannyOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqConvolve2(Image* dest, Image* source, float* kernel, int matrixRows, int matrixCols, float normalize, Image* mask, RoundingMode roundingMode);
+IMAQ_FUNC int IMAQ_STDCALL imaqCorrelate(Image* dest, Image* source, const Image* templateImage, Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqEdgeFilter(Image* dest, Image* source, OutlineMethod method, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqLowPass(Image* dest, Image* source, int width, int height, float tolerance, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqMedianFilter(Image* dest, Image* source, int width, int height, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqNthOrderFilter(Image* dest, Image* source, int width, int height, int n, const Image* mask);
+
+//============================================================================
+// Drawing functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqDrawLineOnImage(Image* dest, const Image* source, DrawMode mode, Point start, Point end, float newPixelValue);
+IMAQ_FUNC int IMAQ_STDCALL imaqDrawShapeOnImage(Image* dest, const Image* source, Rect rect, DrawMode mode, ShapeMode shape, float newPixelValue);
+IMAQ_FUNC int IMAQ_STDCALL imaqDrawTextOnImage(Image* dest, const Image* source, Point coord, const char* text, const DrawTextOptions* options, int* fontNameUsed);
+
+//============================================================================
+// Interlacing functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqInterlaceCombine(Image* frame, const Image* odd, const Image* even);
+IMAQ_FUNC int IMAQ_STDCALL imaqInterlaceSeparate(const Image* frame, Image* odd, Image* even);
+
+//============================================================================
+// Image Information functions
+//============================================================================
+IMAQ_FUNC char** IMAQ_STDCALL imaqEnumerateCustomKeys(const Image* image, unsigned int* size);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetBitDepth(const Image* image, unsigned int* bitDepth);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetBytesPerPixel(const Image* image, int* byteCount);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetImageInfo(const Image* image, ImageInfo* info);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetImageSize(const Image* image, int* width, int* height);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetImageType(const Image* image, ImageType* type);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetMaskOffset(const Image* image, Point* offset);
+IMAQ_FUNC void* IMAQ_STDCALL imaqGetPixelAddress(const Image* image, Point pixel);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetVisionInfoTypes(const Image* image, unsigned int* present);
+IMAQ_FUNC int IMAQ_STDCALL imaqIsImageEmpty(const Image* image, int* empty);
+IMAQ_FUNC void* IMAQ_STDCALL imaqReadCustomData(const Image* image, const char* key, unsigned int* size);
+IMAQ_FUNC int IMAQ_STDCALL imaqRemoveCustomData(Image* image, const char* key);
+IMAQ_FUNC int IMAQ_STDCALL imaqRemoveVisionInfo2(const Image* image, unsigned int info);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetBitDepth(Image* image, unsigned int bitDepth);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetImageSize(Image* image, int width, int height);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetMaskOffset(Image* image, Point offset);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteCustomData(Image* image, const char* key, const void* data, unsigned int size);
+
+//============================================================================
+// Display functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqAreToolsContextSensitive(int* sensitive);
+IMAQ_FUNC int IMAQ_STDCALL imaqCloseWindow(int windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL imaqDisplayImage(const Image* image, int windowNumber, int resize);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetLastKey(char* keyPressed, int* windowNumber, int* modifiers);
+IMAQ_FUNC void* IMAQ_STDCALL imaqGetSystemWindowHandle(int windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetWindowCenterPos(int windowNumber, Point* centerPosition);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetToolContextSensitivity(int sensitive);
+IMAQ_FUNC int IMAQ_STDCALL imaqShowWindow(int windowNumber, int visible);
+
+//============================================================================
+// Image Manipulation functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCast(Image* dest, const Image* source, ImageType type, const float* lookup, int shift);
+IMAQ_FUNC int IMAQ_STDCALL imaqCopyRect(Image* dest, const Image* source, Rect rect, Point destLoc);
+IMAQ_FUNC int IMAQ_STDCALL imaqDuplicate(Image* dest, const Image* source);
+IMAQ_FUNC void* IMAQ_STDCALL imaqFlatten(const Image* image, FlattenType type, CompressionType compression, int quality, unsigned int* size);
+IMAQ_FUNC int IMAQ_STDCALL imaqFlip(Image* dest, const Image* source, FlipAxis axis);
+IMAQ_FUNC int IMAQ_STDCALL imaqMask(Image* dest, const Image* source, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqResample(Image* dest, const Image* source, int newWidth, int newHeight, InterpolationMethod method, Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqRotate2(Image* dest, const Image* source, float angle, PixelValue fill, InterpolationMethod method, int maintainSize);
+IMAQ_FUNC int IMAQ_STDCALL imaqScale(Image* dest, const Image* source, int xScale, int yScale, ScalingMode scaleMode, Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqShift(Image* dest, const Image* source, int shiftX, int shiftY, PixelValue fill);
+IMAQ_FUNC int IMAQ_STDCALL imaqTranspose(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqUnflatten(Image* image, const void* data, unsigned int size);
+IMAQ_FUNC int IMAQ_STDCALL imaqUnwrapImage(Image* dest, const Image* source, Annulus annulus, RectOrientation orientation, InterpolationMethod method);
+IMAQ_FUNC int IMAQ_STDCALL imaqView3D(Image* dest, Image* source, const View3DOptions* options);
+
+//============================================================================
+// File I/O functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCloseAVI(AVISession session);
+IMAQ_FUNC AVISession IMAQ_STDCALL imaqCreateAVI(const char* fileName, const char* compressionFilter, int quality, unsigned int framesPerSecond, unsigned int maxDataSize);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetAVIInfo(AVISession session, AVIInfo* info);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetFileInfo(const char* fileName, CalibrationUnit* calibrationUnit, float* calibrationX, float* calibrationY, int* width, int* height, ImageType* imageType);
+IMAQ_FUNC FilterName* IMAQ_STDCALL imaqGetFilterNames(int* numFilters);
+IMAQ_FUNC char** IMAQ_STDCALL imaqLoadImagePopup(const char* defaultDirectory, const char* defaultFileSpec, const char* fileTypeList, const char* title, int allowMultiplePaths, ButtonLabel buttonLabel, int restrictDirectory, int restrictExtension, int allowCancel, int allowMakeDirectory, int* cancelled, int* numPaths);
+IMAQ_FUNC AVISession IMAQ_STDCALL imaqOpenAVI(const char* fileName);
+IMAQ_FUNC int IMAQ_STDCALL imaqReadAVIFrame(Image* image, AVISession session, unsigned int frameNum, void* data, unsigned int* dataSize);
+IMAQ_FUNC int IMAQ_STDCALL imaqReadFile(Image* image, const char* fileName, RGBValue* colorTable, int* numColors);
+IMAQ_FUNC int IMAQ_STDCALL imaqReadVisionFile(Image* image, const char* fileName, RGBValue* colorTable, int* numColors);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteAVIFrame(Image* image, AVISession session, const void* data, unsigned int dataLength);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteBMPFile(const Image* image, const char* fileName, int compress, const RGBValue* colorTable);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteFile(const Image* image, const char* fileName, const RGBValue* colorTable);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteJPEGFile(const Image* image, const char* fileName, unsigned int quality, void* colorTable);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteJPEG2000File(const Image* image, const char* fileName, int lossless, float compressionRatio, const JPEG2000FileAdvancedOptions* advancedOptions, const RGBValue* colorTable);
+IMAQ_FUNC int IMAQ_STDCALL imaqWritePNGFile2(const Image* image, const char* fileName, unsigned int compressionSpeed, const RGBValue* colorTable, int useBitDepth);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteTIFFFile(const Image* image, const char* fileName, const TIFFFileOptions* options, const RGBValue* colorTable);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteVisionFile(const Image* image, const char* fileName, const RGBValue* colorTable);
+
+
+//============================================================================
+// Analytic Geometry functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqBuildCoordinateSystem(const Point* points, ReferenceMode mode, AxisOrientation orientation, CoordinateSystem* system);
+IMAQ_FUNC BestCircle2* IMAQ_STDCALL imaqFitCircle2(const PointFloat* points, int numPoints, const FitCircleOptions* options);
+IMAQ_FUNC BestEllipse2* IMAQ_STDCALL imaqFitEllipse2(const PointFloat* points, int numPoints, const FitEllipseOptions* options);
+IMAQ_FUNC BestLine* IMAQ_STDCALL imaqFitLine(const PointFloat* points, int numPoints, const FitLineOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetAngle(PointFloat start1, PointFloat end1, PointFloat start2, PointFloat end2, float* angle);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetBisectingLine(PointFloat start1, PointFloat end1, PointFloat start2, PointFloat end2, PointFloat* bisectStart, PointFloat* bisectEnd);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetDistance(PointFloat point1, PointFloat point2, float* distance);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetIntersection(PointFloat start1, PointFloat end1, PointFloat start2, PointFloat end2, PointFloat* intersection);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetMidLine(PointFloat refLineStart, PointFloat refLineEnd, PointFloat point, PointFloat* midLineStart, PointFloat* midLineEnd);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetPerpendicularLine(PointFloat refLineStart, PointFloat refLineEnd, PointFloat point, PointFloat* perpLineStart, PointFloat* perpLineEnd, double* distance);
+IMAQ_FUNC SegmentInfo* IMAQ_STDCALL imaqGetPointsOnContour(const Image* image, int* numSegments);
+IMAQ_FUNC Point* IMAQ_STDCALL imaqGetPointsOnLine(Point start, Point end, int* numPoints);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetPolygonArea(const PointFloat* points, int numPoints, float* area);
+IMAQ_FUNC float* IMAQ_STDCALL imaqInterpolatePoints(const Image* image, const Point* points, int numPoints, InterpolationMethod method, int subpixel, int* interpCount);
+
+//============================================================================
+// Clipboard functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqClipboardToImage(Image* dest, RGBValue* palette);
+IMAQ_FUNC int IMAQ_STDCALL imaqImageToClipboard(const Image* image, const RGBValue* palette);
+
+//============================================================================
+// Border functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqFillBorder(Image* image, BorderMethod method);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetBorderSize(const Image* image, int* borderSize);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetBorderSize(Image* image, int size);
+
+//============================================================================
+// Image Management functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqArrayToImage(Image* image, const void* array, int numCols, int numRows);
+IMAQ_FUNC Image* IMAQ_STDCALL imaqCreateImage(ImageType type, int borderSize);
+IMAQ_FUNC void* IMAQ_STDCALL imaqImageToArray(const Image* image, Rect rect, int* columns, int* rows);
+
+//============================================================================
+// Color Processing functions
+//============================================================================
+IMAQ_FUNC Color2 IMAQ_STDCALL imaqChangeColorSpace2(const Color2* sourceColor, ColorMode sourceSpace, ColorMode destSpace, double offset, const CIEXYZValue* whiteReference);
+IMAQ_FUNC int IMAQ_STDCALL imaqColorBCGTransform(Image* dest, const Image* source, const BCGOptions* redOptions, const BCGOptions* greenOptions, const BCGOptions* blueOptions, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqColorEqualize(Image* dest, const Image* source, int colorEqualization);
+IMAQ_FUNC ColorHistogramReport* IMAQ_STDCALL imaqColorHistogram2(Image* image, int numClasses, ColorMode mode, const CIEXYZValue* whiteReference, Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqColorLookup(Image* dest, const Image* source, ColorMode mode, const Image* mask, const short* plane1, const short* plane2, const short* plane3);
+IMAQ_FUNC int IMAQ_STDCALL imaqColorThreshold(Image* dest, const Image* source, int replaceValue, ColorMode mode, const Range* plane1Range, const Range* plane2Range, const Range* plane3Range);
+IMAQ_FUNC SupervisedColorSegmentationReport* IMAQ_STDCALL imaqSupervisedColorSegmentation(ClassifierSession* session, Image* labelImage, const Image* srcImage, const ROI* roi, const ROILabel* labelIn, unsigned int numLabelIn, int maxDistance, int minIdentificationScore, const ColorSegmenationOptions* segmentOptions);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetColorSegmentationMaxDistance(ClassifierSession* session, const ColorSegmenationOptions* segmentOptions, SegmentationDistanceLevel distLevel, int* maxDistance);
+
+//============================================================================
+// Transform functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqBCGTransform(Image* dest, const Image* source, const BCGOptions* options, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqEqualize(Image* dest, const Image* source, float min, float max, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqInverse(Image* dest, const Image* source, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqMathTransform(Image* dest, const Image* source, MathTransformMethod method, float rangeMin, float rangeMax, float power, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqWatershedTransform(Image* dest, const Image* source, int connectivity8, int* zoneCount);
+IMAQ_FUNC int IMAQ_STDCALL imaqLookup2(Image* dest, const Image* source, const int* table, const Image* mask);
+
+
+//============================================================================
+// Window Management functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqAreScrollbarsVisible(int windowNumber, int* visible);
+IMAQ_FUNC int IMAQ_STDCALL imaqBringWindowToTop(int windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetMousePos(Point* position, int* windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetWindowBackground(int windowNumber, WindowBackgroundFillStyle* fillStyle, WindowBackgroundHatchStyle* hatchStyle, RGBValue* fillColor, RGBValue* backgroundColor);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetWindowDisplayMapping(int windowNum, DisplayMapping* mapping);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetWindowGrid(int windowNumber, int* xResolution, int* yResolution);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetWindowHandle(int* handle);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetWindowPos(int windowNumber, Point* position);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetWindowSize(int windowNumber, int* width, int* height);
+IMAQ_FUNC char* IMAQ_STDCALL imaqGetWindowTitle(int windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetWindowZoom2(int windowNumber, float* xZoom, float* yZoom);
+IMAQ_FUNC int IMAQ_STDCALL imaqIsWindowNonTearing(int windowNumber, int* nonTearing);
+IMAQ_FUNC int IMAQ_STDCALL imaqIsWindowVisible(int windowNumber, int* visible);
+IMAQ_FUNC int IMAQ_STDCALL imaqMoveWindow(int windowNumber, Point position);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetupWindow(int windowNumber, int configuration);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowBackground(int windowNumber, WindowBackgroundFillStyle fillStyle, WindowBackgroundHatchStyle hatchStyle, const RGBValue* fillColor, const RGBValue* backgroundColor);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowDisplayMapping(int windowNumber, const DisplayMapping* mapping);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowGrid(int windowNumber, int xResolution, int yResolution);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowMaxContourCount(int windowNumber, unsigned int maxContourCount);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowNonTearing(int windowNumber, int nonTearing);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowPalette(int windowNumber, PaletteType type, const RGBValue* palette, int numColors);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowSize(int windowNumber, int width, int height);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowThreadPolicy(WindowThreadPolicy policy);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowTitle(int windowNumber, const char* title);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowZoomToFit(int windowNumber, int zoomToFit);
+IMAQ_FUNC int IMAQ_STDCALL imaqShowScrollbars(int windowNumber, int visible);
+IMAQ_FUNC int IMAQ_STDCALL imaqZoomWindow2(int windowNumber, float xZoom, float yZoom, Point center);
+
+//============================================================================
+// Utilities functions
+//============================================================================
+IMAQ_FUNC const float* IMAQ_STDCALL imaqGetKernel(KernelFamily family, int size, int number);
+IMAQ_FUNC Annulus IMAQ_STDCALL imaqMakeAnnulus(Point center, int innerRadius, int outerRadius, double startAngle, double endAngle);
+IMAQ_FUNC Point IMAQ_STDCALL imaqMakePoint(int xCoordinate, int yCoordinate);
+IMAQ_FUNC PointFloat IMAQ_STDCALL imaqMakePointFloat(float xCoordinate, float yCoordinate);
+IMAQ_FUNC Rect IMAQ_STDCALL imaqMakeRect(int top, int left, int height, int width);
+IMAQ_FUNC Rect IMAQ_STDCALL imaqMakeRectFromRotatedRect(RotatedRect rotatedRect);
+IMAQ_FUNC RotatedRect IMAQ_STDCALL imaqMakeRotatedRect(int top, int left, int height, int width, double angle);
+IMAQ_FUNC RotatedRect IMAQ_STDCALL imaqMakeRotatedRectFromRect(Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqMulticoreOptions(MulticoreOperation operation, unsigned int* customNumCores);
+
+//============================================================================
+// Tool Window functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCloseToolWindow(void);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetCurrentTool(Tool* currentTool);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetLastEvent(WindowEventType* type, int* windowNumber, Tool* tool, Rect* rect);
+IMAQ_FUNC void* IMAQ_STDCALL imaqGetToolWindowHandle(void);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetToolWindowPos(Point* position);
+IMAQ_FUNC int IMAQ_STDCALL imaqIsToolWindowVisible(int* visible);
+IMAQ_FUNC int IMAQ_STDCALL imaqMoveToolWindow(Point position);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetCurrentTool(Tool currentTool);
+#ifndef __GNUC__
+IMAQ_FUNC int IMAQ_STDCALL imaqSetEventCallback(EventCallback callback, int synchronous);
+#endif
+IMAQ_FUNC int IMAQ_STDCALL imaqSetToolColor(const RGBValue* color);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetupToolWindow(int showCoordinates, int maxIconsPerLine, const ToolWindowOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqShowToolWindow(int visible);
+
+//============================================================================
+// Meter functions
+//============================================================================
+IMAQ_FUNC MeterArc* IMAQ_STDCALL imaqGetMeterArc(int lightNeedle, MeterArcMode mode, const ROI* roi, PointFloat base, PointFloat start, PointFloat end);
+IMAQ_FUNC int IMAQ_STDCALL imaqReadMeter(const Image* image, const MeterArc* arcInfo, double* percentage, PointFloat* endOfNeedle);
+
+//============================================================================
+// Calibration functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCopyCalibrationInfo2(Image* dest, Image* source, Point offset);
+IMAQ_FUNC int IMAQ_STDCALL imaqCorrectCalibratedImage(Image* dest, const Image* source, PixelValue fill, InterpolationMethod method, const ROI* roi);
+IMAQ_FUNC CalibrationInfo* IMAQ_STDCALL imaqGetCalibrationInfo2(const Image* image);
+IMAQ_FUNC CalibrationInfo* IMAQ_STDCALL imaqGetCalibrationInfo3(Image* image, unsigned int isGetErrorMap);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnCalibrationGrid(Image* image, const ROI* roi, const LearnCalibrationOptions* options, const GridDescriptor* grid, const CoordinateSystem* system, const RangeFloat* range, float* quality);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnCalibrationPoints(Image* image, const CalibrationPoints* points, const ROI* roi, const LearnCalibrationOptions* options, const GridDescriptor* grid, const CoordinateSystem* system, float* quality);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetCoordinateSystem(Image* image, const CoordinateSystem* system);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetSimpleCalibration(Image* image, ScalingMethod method, int learnTable, const GridDescriptor* grid, const CoordinateSystem* system);
+IMAQ_FUNC TransformReport* IMAQ_STDCALL imaqTransformPixelToRealWorld(const Image* image, const PointFloat* pixelCoordinates, int numCoordinates);
+IMAQ_FUNC TransformReport* IMAQ_STDCALL imaqTransformRealWorldToPixel(const Image* image, const PointFloat* realWorldCoordinates, int numCoordinates);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetSimpleCalibration2(Image* image, const GridDescriptor* gridDescriptor);
+IMAQ_FUNC int IMAQ_STDCALL imaqCalibrationSetAxisInfo(Image* image, CoordinateSystem* axisInfo);
+IMAQ_FUNC int IMAQ_STDCALL imaqCalibrationGetThumbnailImage(Image* templateImage, Image* image, CalibrationThumbnailType type, unsigned int index);
+IMAQ_FUNC GetCalibrationInfoReport* IMAQ_STDCALL imaqCalibrationGetCalibrationInfo(Image* image, unsigned int isGetErrorMap);
+IMAQ_FUNC GetCameraParametersReport* IMAQ_STDCALL imaqCalibrationGetCameraParameters(Image* templateImage);
+IMAQ_FUNC int IMAQ_STDCALL imaqCalibrationCompactInformation(Image* image);
+
+//============================================================================
+// Pixel Manipulation functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqArrayToComplexPlane(Image* dest, const Image* source, const float* newPixels, ComplexPlane plane);
+IMAQ_FUNC float* IMAQ_STDCALL imaqComplexPlaneToArray(const Image* image, ComplexPlane plane, Rect rect, int* rows, int* columns);
+IMAQ_FUNC int IMAQ_STDCALL imaqExtractColorPlanes(const Image* image, ColorMode mode, Image* plane1, Image* plane2, Image* plane3);
+IMAQ_FUNC int IMAQ_STDCALL imaqExtractComplexPlane(Image* dest, const Image* source, ComplexPlane plane);
+IMAQ_FUNC int IMAQ_STDCALL imaqFillImage(Image* image, PixelValue value, const Image* mask);
+IMAQ_FUNC void* IMAQ_STDCALL imaqGetLine(const Image* image, Point start, Point end, int* numPoints);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetPixel(const Image* image, Point pixel, PixelValue* value);
+IMAQ_FUNC int IMAQ_STDCALL imaqReplaceColorPlanes(Image* dest, const Image* source, ColorMode mode, const Image* plane1, const Image* plane2, const Image* plane3);
+IMAQ_FUNC int IMAQ_STDCALL imaqReplaceComplexPlane(Image* dest, const Image* source, const Image* newValues, ComplexPlane plane);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetLine(Image* image, const void* array, int arraySize, Point start, Point end);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetPixel(Image* image, Point coord, PixelValue value);
+
+//============================================================================
+// Color Matching functions
+//============================================================================
+IMAQ_FUNC ColorInformation* IMAQ_STDCALL imaqLearnColor(const Image* image, const ROI* roi, ColorSensitivity sensitivity, int saturation);
+IMAQ_FUNC int* IMAQ_STDCALL imaqMatchColor(const Image* image, const ColorInformation* info, const ROI* roi, int* numScores);
+
+//============================================================================
+// Frequency Domain Analysis functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqAttenuate(Image* dest, const Image* source, AttenuateMode highlow);
+IMAQ_FUNC int IMAQ_STDCALL imaqConjugate(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqFFT(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqFlipFrequencies(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqInverseFFT(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqTruncate(Image* dest, const Image* source, TruncateMode highlow, float ratioToKeep);
+
+//============================================================================
+// Barcode I/O functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqGradeDataMatrixBarcodeAIM(const Image* image, AIMGradeReport* report);
+IMAQ_FUNC BarcodeInfo* IMAQ_STDCALL imaqReadBarcode(const Image* image, BarcodeType type, const ROI* roi, int validate);
+IMAQ_FUNC DataMatrixReport* IMAQ_STDCALL imaqReadDataMatrixBarcode2(Image* image, const ROI* roi, DataMatrixGradingMode prepareForGrading, const DataMatrixDescriptionOptions* descriptionOptions, const DataMatrixSizeOptions* sizeOptions, const DataMatrixSearchOptions* searchOptions);
+IMAQ_FUNC Barcode2DInfo* IMAQ_STDCALL imaqReadPDF417Barcode(const Image* image, const ROI* roi, Barcode2DSearchMode searchMode, unsigned int* numBarcodes);
+IMAQ_FUNC QRCodeReport* IMAQ_STDCALL imaqReadQRCode(Image* image, const ROI* roi, QRGradingMode reserved, const QRCodeDescriptionOptions* descriptionOptions, const QRCodeSizeOptions* sizeOptions, const QRCodeSearchOptions* searchOptions);
+
+//============================================================================
+// LCD functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqFindLCDSegments(ROI* roi, const Image* image, const LCDOptions* options);
+IMAQ_FUNC LCDReport* IMAQ_STDCALL imaqReadLCD(const Image* image, const ROI* roi, const LCDOptions* options);
+
+//============================================================================
+// Shape Matching functions
+//============================================================================
+IMAQ_FUNC ShapeReport* IMAQ_STDCALL imaqMatchShape(Image* dest, Image* source, const Image* templateImage, int scaleInvariant, int connectivity8, double tolerance, int* numMatches);
+
+//============================================================================
+// Contours functions
+//============================================================================
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddAnnulusContour(ROI* roi, Annulus annulus);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddClosedContour(ROI* roi, const Point* points, int numPoints);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddLineContour(ROI* roi, Point start, Point end);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddOpenContour(ROI* roi, const Point* points, int numPoints);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddOvalContour(ROI* roi, Rect boundingBox);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddPointContour(ROI* roi, Point point);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddRectContour(ROI* roi, Rect rect);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddRotatedRectContour2(ROI* roi, RotatedRect rect);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqCopyContour(ROI* destRoi, const ROI* sourceRoi, ContourID id);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqGetContour(const ROI* roi, unsigned int index);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetContourColor(const ROI* roi, ContourID id, RGBValue* contourColor);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetContourCount(const ROI* roi);
+IMAQ_FUNC ContourInfo2* IMAQ_STDCALL imaqGetContourInfo2(const ROI* roi, ContourID id);
+IMAQ_FUNC int IMAQ_STDCALL imaqMoveContour(ROI* roi, ContourID id, int deltaX, int deltaY);
+IMAQ_FUNC int IMAQ_STDCALL imaqRemoveContour(ROI* roi, ContourID id);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetContourColor(ROI* roi, ContourID id, const RGBValue* color);
+
+//============================================================================
+// Regions of Interest functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqConstructROI2(const Image* image, ROI* roi, Tool initialTool, const ToolWindowOptions* tools, const ConstructROIOptions2* options, int* okay);
+IMAQ_FUNC ROI* IMAQ_STDCALL imaqCreateROI(void);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetROIBoundingBox(const ROI* roi, Rect* boundingBox);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetROIColor(const ROI* roi, RGBValue* roiColor);
+IMAQ_FUNC ROI* IMAQ_STDCALL imaqGetWindowROI(int windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetROIColor(ROI* roi, const RGBValue* color);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowROI(int windowNumber, const ROI* roi);
+
+//============================================================================
+// Image Analysis functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCentroid(const Image* image, PointFloat* centroid, const Image* mask);
+IMAQ_FUNC Curve* IMAQ_STDCALL imaqExtractCurves(const Image* image, const ROI* roi, const CurveOptions* curveOptions, unsigned int* numCurves);
+IMAQ_FUNC HistogramReport* IMAQ_STDCALL imaqHistogram(const Image* image, int numClasses, float min, float max, const Image* mask);
+IMAQ_FUNC LinearAverages* IMAQ_STDCALL imaqLinearAverages2(Image* image, LinearAveragesMode mode, Rect rect);
+IMAQ_FUNC LineProfile* IMAQ_STDCALL imaqLineProfile(const Image* image, Point start, Point end);
+IMAQ_FUNC QuantifyReport* IMAQ_STDCALL imaqQuantify(const Image* image, const Image* mask);
+
+//============================================================================
+// Error Management functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqClearError(void);
+IMAQ_FUNC char* IMAQ_STDCALL imaqGetErrorText(int errorCode);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetLastError(void);
+IMAQ_FUNC const char* IMAQ_STDCALL imaqGetLastErrorFunc(void);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetError(int errorCode, const char* function);
+
+//============================================================================
+// Threshold functions
+//============================================================================
+IMAQ_FUNC ThresholdData* IMAQ_STDCALL imaqAutoThreshold2(Image* dest, const Image* source, int numClasses, ThresholdMethod method, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqLocalThreshold(Image* dest, const Image* source, unsigned int windowWidth, unsigned int windowHeight, LocalThresholdMethod method, double deviationWeight, ObjectType type, float replaceValue);
+IMAQ_FUNC int IMAQ_STDCALL imaqMagicWand(Image* dest, const Image* source, Point coord, float tolerance, int connectivity8, float replaceValue);
+IMAQ_FUNC int IMAQ_STDCALL imaqMultithreshold(Image* dest, const Image* source, const ThresholdData* ranges, int numRanges);
+IMAQ_FUNC int IMAQ_STDCALL imaqThreshold(Image* dest, const Image* source, float rangeMin, float rangeMax, int useNewValue, float newValue);
+
+//============================================================================
+// Memory Management functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqDispose(void* object);
+
+//============================================================================
+// Pattern Matching functions
+//============================================================================
+IMAQ_FUNC CircleMatch* IMAQ_STDCALL imaqDetectCircles(const Image* image, const CircleDescriptor* circleDescriptor, const CurveOptions* curveOptions, const ShapeDetectionOptions* shapeDetectionOptions, const ROI* roi, int* numMatchesReturned);
+IMAQ_FUNC EllipseMatch* IMAQ_STDCALL imaqDetectEllipses(const Image* image, const EllipseDescriptor* ellipseDescriptor, const CurveOptions* curveOptions, const ShapeDetectionOptions* shapeDetectionOptions, const ROI* roi, int* numMatchesReturned);
+IMAQ_FUNC LineMatch* IMAQ_STDCALL imaqDetectLines(const Image* image, const LineDescriptor* lineDescriptor, const CurveOptions* curveOptions, const ShapeDetectionOptions* shapeDetectionOptions, const ROI* roi, int* numMatchesReturned);
+IMAQ_FUNC RectangleMatch* IMAQ_STDCALL imaqDetectRectangles(const Image* image, const RectangleDescriptor* rectangleDescriptor, const CurveOptions* curveOptions, const ShapeDetectionOptions* shapeDetectionOptions, const ROI* roi, int* numMatchesReturned);
+IMAQ_FUNC FeatureData* IMAQ_STDCALL imaqGetGeometricFeaturesFromCurves(const Curve* curves, unsigned int numCurves, const FeatureType* featureTypes, unsigned int numFeatureTypes, unsigned int* numFeatures);
+IMAQ_FUNC FeatureData* IMAQ_STDCALL imaqGetGeometricTemplateFeatureInfo(const Image* pattern, unsigned int* numFeatures);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnColorPattern(Image* image, const LearnColorPatternOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnGeometricPattern(Image* image, PointFloat originOffset, const CurveOptions* curveOptions, const LearnGeometricPatternAdvancedOptions* advancedLearnOptions, const Image* mask);
+IMAQ_FUNC MultipleGeometricPattern* IMAQ_STDCALL imaqLearnMultipleGeometricPatterns(const Image** patterns, unsigned int numberOfPatterns, const String255* labels);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnPattern3(Image* image, LearningMode learningMode, LearnPatternAdvancedOptions* advancedOptions, const Image* mask);
+IMAQ_FUNC PatternMatch* IMAQ_STDCALL imaqMatchColorPattern(const Image* image, Image* pattern, const MatchColorPatternOptions* options, Rect searchRect, int* numMatches);
+IMAQ_FUNC GeometricPatternMatch2* IMAQ_STDCALL imaqMatchGeometricPattern2(const Image* image, const Image* pattern, const CurveOptions* curveOptions, const MatchGeometricPatternOptions* matchOptions, const MatchGeometricPatternAdvancedOptions2* advancedMatchOptions, const ROI* roi, int* numMatches);
+IMAQ_FUNC GeometricPatternMatch2* IMAQ_STDCALL imaqMatchMultipleGeometricPatterns(const Image* image, const MultipleGeometricPattern* multiplePattern, const ROI* roi, int* numMatches);
+IMAQ_FUNC MultipleGeometricPattern* IMAQ_STDCALL imaqReadMultipleGeometricPatternFile(const char* fileName, String255 description);
+IMAQ_FUNC PatternMatch* IMAQ_STDCALL imaqRefineMatches(const Image* image, const Image* pattern, const PatternMatch* candidatesIn, int numCandidatesIn, MatchPatternOptions* options, MatchPatternAdvancedOptions* advancedOptions, int* numCandidatesOut);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetMultipleGeometricPatternsOptions(MultipleGeometricPattern* multiplePattern, const char* label, const CurveOptions* curveOptions, const MatchGeometricPatternOptions* matchOptions, const MatchGeometricPatternAdvancedOptions2* advancedMatchOptions);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteMultipleGeometricPatternFile(const MultipleGeometricPattern* multiplePattern, const char* fileName, const char* description);
+IMAQ_FUNC GeometricPatternMatch3* IMAQ_STDCALL imaqMatchGeometricPattern3(const Image* image, const Image* pattern, const CurveOptions* curveOptions, const MatchGeometricPatternOptions* matchOptions, const MatchGeometricPatternAdvancedOptions3* advancedMatchOptions, const ROI* roi, size_t* numMatches);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnGeometricPattern2(Image* image, PointFloat originOffset, double angleOffset, const CurveOptions* curveOptions, const LearnGeometricPatternAdvancedOptions2* advancedLearnOptions, const Image* mask);
+IMAQ_FUNC PatternMatch* IMAQ_STDCALL imaqMatchPattern3(const Image* image, const Image* pattern, const MatchPatternOptions* options, const MatchPatternAdvancedOptions* advancedOptions, const ROI* roi, int* numMatches);
+
+//============================================================================
+// Overlay functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqClearOverlay(Image* image, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqCopyOverlay(Image* dest, const Image* source, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetOverlayProperties(const Image* image, const char* group, TransformBehaviors* transformBehaviors);
+IMAQ_FUNC int IMAQ_STDCALL imaqMergeOverlay(Image* dest, const Image* source, const RGBValue* palette, unsigned int numColors, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayArc(Image* image, const ArcInfo* arc, const RGBValue* color, DrawMode drawMode, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayBitmap(Image* image, Point destLoc, const RGBValue* bitmap, unsigned int numCols, unsigned int numRows, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayClosedContour(Image* image, const Point* points, int numPoints, const RGBValue* color, DrawMode drawMode, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayLine(Image* image, Point start, Point end, const RGBValue* color, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayMetafile(Image* image, const void* metafile, Rect rect, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayOpenContour(Image* image, const Point* points, int numPoints, const RGBValue* color, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayOval(Image* image, Rect boundingBox, const RGBValue* color, DrawMode drawMode, char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayPoints(Image* image, const Point* points, int numPoints, const RGBValue* colors, int numColors, PointSymbol symbol, const UserPointSymbol* userSymbol, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayRect(Image* image, Rect rect, const RGBValue* color, DrawMode drawMode, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayROI(Image* image, const ROI* roi, PointSymbol symbol, const UserPointSymbol* userSymbol, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayText(Image* image, Point origin, const char* text, const RGBValue* color, const OverlayTextOptions* options, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetOverlayProperties(Image* image, const char* group, TransformBehaviors* transformBehaviors);
+
+//============================================================================
+// OCR functions
+//============================================================================
+IMAQ_FUNC CharSet* IMAQ_STDCALL imaqCreateCharSet(void);
+IMAQ_FUNC int IMAQ_STDCALL imaqDeleteChar(CharSet* set, int index);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetCharCount(const CharSet* set);
+IMAQ_FUNC CharInfo2* IMAQ_STDCALL imaqGetCharInfo2(const CharSet* set, int index);
+IMAQ_FUNC int IMAQ_STDCALL imaqReadOCRFile(const char* fileName, CharSet* set, String255 setDescription, ReadTextOptions* readOptions, OCRProcessingOptions* processingOptions, OCRSpacingOptions* spacingOptions);
+IMAQ_FUNC ReadTextReport3* IMAQ_STDCALL imaqReadText3(const Image* image, const CharSet* set, const ROI* roi, const ReadTextOptions* readOptions, const OCRProcessingOptions* processingOptions, const OCRSpacingOptions* spacingOptions);
+IMAQ_FUNC int IMAQ_STDCALL imaqRenameChar(CharSet* set, int index, const char* newCharValue);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetReferenceChar(const CharSet* set, int index, int isReferenceChar);
+IMAQ_FUNC int IMAQ_STDCALL imaqTrainChars(const Image* image, CharSet* set, int index, const char* charValue, const ROI* roi, const OCRProcessingOptions* processingOptions, const OCRSpacingOptions* spacingOptions);
+IMAQ_FUNC int* IMAQ_STDCALL imaqVerifyPatterns(const Image* image, const CharSet* set, const String255* expectedPatterns, int patternCount, const ROI* roi, int* numScores);
+IMAQ_FUNC int* IMAQ_STDCALL imaqVerifyText(const Image* image, const CharSet* set, const char* expectedString, const ROI* roi, int* numScores);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteOCRFile(const char* fileName, const CharSet* set, const char* setDescription, const ReadTextOptions* readOptions, const OCRProcessingOptions* processingOptions, const OCRSpacingOptions* spacingOptions);
+
+//============================================================================
+// Geometric Matching functions
+//============================================================================
+IMAQ_FUNC ExtractContourReport* IMAQ_STDCALL imaqExtractContour(Image* image, const ROI* roi, ExtractContourDirection direction, CurveParameters* curveParams, const ConnectionConstraint* connectionConstraintParams, unsigned int numOfConstraints, ExtractContourSelection selection, Image* contourImage);
+IMAQ_FUNC int IMAQ_STDCALL imaqContourOverlay(Image* image, const Image* contourImage, const ContourOverlaySettings* pointsSettings, const ContourOverlaySettings* eqnSettings, const char* groupName);
+IMAQ_FUNC ContourComputeCurvatureReport* IMAQ_STDCALL imaqContourComputeCurvature(const Image* contourImage, unsigned int kernel);
+IMAQ_FUNC CurvatureAnalysisReport* IMAQ_STDCALL imaqContourClassifyCurvature(const Image* contourImage, unsigned int kernel, RangeLabel* curvatureClasses, unsigned int numCurvatureClasses);
+IMAQ_FUNC ComputeDistancesReport* IMAQ_STDCALL imaqContourComputeDistances(const Image* targetImage, const Image* templateImage, const SetupMatchPatternData* matchSetupData, unsigned int smoothingKernel);
+IMAQ_FUNC ClassifyDistancesReport* IMAQ_STDCALL imaqContourClassifyDistances(const Image* targetImage, const Image* templateImage, const SetupMatchPatternData* matchSetupData, unsigned int smoothingKernel, const RangeLabel* distanceRanges, unsigned int numDistanceRanges);
+IMAQ_FUNC ContourInfoReport* IMAQ_STDCALL imaqContourInfo(const Image* contourImage);
+IMAQ_FUNC SetupMatchPatternData* IMAQ_STDCALL imaqContourSetupMatchPattern(MatchMode* matchMode, unsigned int enableSubPixelAccuracy, CurveParameters* curveParams, unsigned int useLearnCurveParameters, const RangeSettingDouble* rangeSettings, unsigned int numRangeSettings);
+IMAQ_FUNC int IMAQ_STDCALL imaqContourAdvancedSetupMatchPattern(SetupMatchPatternData* matchSetupData, GeometricAdvancedSetupDataOption* geometricOptions, unsigned int numGeometricOptions);
+IMAQ_FUNC ContourFitLineReport* IMAQ_STDCALL imaqContourFitLine(Image* image, double pixelRadius);
+IMAQ_FUNC PartialCircle* IMAQ_STDCALL imaqContourFitCircle(Image* image, double pixelRadius, int rejectOutliers);
+IMAQ_FUNC PartialEllipse* IMAQ_STDCALL imaqContourFitEllipse(Image* image, double pixelRadius, int rejectOutliers);
+IMAQ_FUNC ContourFitSplineReport* IMAQ_STDCALL imaqContourFitSpline(Image* image, int degree, int numberOfControlPoints);
+IMAQ_FUNC ContourFitPolynomialReport* IMAQ_STDCALL imaqContourFitPolynomial(Image* image, int order);
+
+//============================================================================
+// Edge Detection functions
+//============================================================================
+IMAQ_FUNC FindCircularEdgeReport* IMAQ_STDCALL imaqFindCircularEdge2(Image* image, const ROI* roi, const CoordinateSystem* baseSystem, const CoordinateSystem* newSystem, const FindCircularEdgeOptions* edgeOptions, const CircleFitOptions* circleFitOptions);
+IMAQ_FUNC FindConcentricEdgeReport* IMAQ_STDCALL imaqFindConcentricEdge2(Image* image, const ROI* roi, const CoordinateSystem* baseSystem, const CoordinateSystem* newSystem, const FindConcentricEdgeOptions* edgeOptions, const ConcentricEdgeFitOptions* concentricEdgeFitOptions);
+
+//============================================================================
+// Morphology Reconstruction functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqGrayMorphologyReconstruct(Image* dstImage, Image* srcImage, const Image* markerImage, PointFloat* points, int numOfPoints, MorphologyReconstructOperation operation, const StructuringElement* structuringElement, const ROI* roi);
+IMAQ_FUNC int IMAQ_STDCALL imaqMorphologyReconstruct(Image* dstImage, Image* srcImage, const Image* markerImage, PointFloat* points, int numOfPoints, MorphologyReconstructOperation operation, Connectivity connectivity, const ROI* roi);
+
+//============================================================================
+// Texture functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqDetectTextureDefect(ClassifierSession* session, Image* destImage, const Image* srcImage, const ROI* roi, int initialStepSize, int finalStepSize, unsigned char defectPixelValue, double minClassificationScore);
+IMAQ_FUNC int IMAQ_STDCALL imaqClassificationTextureDefectOptions(ClassifierSession* session, WindowSize* windowOptions, WaveletOptions* waveletOptions, void** bandsUsed, int* numBandsUsed, CooccurrenceOptions* cooccurrenceOptions, unsigned char setOperation);
+IMAQ_FUNC int IMAQ_STDCALL imaqCooccurrenceMatrix(const Image* srcImage, const ROI* roi, int levelPixel, const DisplacementVector* displacementVec, void* featureOptionArray, unsigned int featureOptionArraySize, void** cooccurrenceMatrixArray, int* coocurrenceMatrixRows, int* coocurrenceMatrixCols, void** featureVectorArray, int* featureVectorArraySize);
+IMAQ_FUNC ExtractTextureFeaturesReport* IMAQ_STDCALL imaqExtractTextureFeatures(const Image* srcImage, const ROI* roi, const WindowSize* windowOptions, const WaveletOptions* waveletOptions, void* waveletBands, unsigned int numWaveletBands, const CooccurrenceOptions* cooccurrenceOptions, unsigned char useWindow);
+IMAQ_FUNC WaveletBandsReport* IMAQ_STDCALL imaqExtractWaveletBands(const Image* srcImage, const WaveletOptions* waveletOptions, void* waveletBands, unsigned int numWaveletBands);
+
+//============================================================================
+// Regions of Interest Manipulation functions
+//============================================================================
+IMAQ_FUNC ROI* IMAQ_STDCALL imaqMaskToROI(const Image* mask, int* withinLimit);
+IMAQ_FUNC ROIProfile* IMAQ_STDCALL imaqROIProfile(const Image* image, const ROI* roi);
+IMAQ_FUNC int IMAQ_STDCALL imaqROIToMask(Image* mask, const ROI* roi, int fillValue, const Image* imageModel, int* inSpace);
+IMAQ_FUNC int IMAQ_STDCALL imaqTransformROI2(ROI* roi, const CoordinateSystem* baseSystem, const CoordinateSystem* newSystem);
+IMAQ_FUNC LabelToROIReport* IMAQ_STDCALL imaqLabelToROI(const Image* image, const unsigned int* labelsIn, unsigned int numLabelsIn, int maxNumVectors, int isExternelEdges);
+
+//============================================================================
+// Morphology functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqGrayMorphology(Image* dest, Image* source, MorphologyMethod method, const StructuringElement* structuringElement);
+
+//============================================================================
+// Classification functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqAddClassifierSample(Image* image, ClassifierSession* session, const ROI* roi, const char* sampleClass, double* featureVector, unsigned int vectorSize);
+IMAQ_FUNC ClassifierReportAdvanced* IMAQ_STDCALL imaqAdvanceClassify(Image* image, const ClassifierSession* session, const ROI* roi, double* featureVector, unsigned int vectorSize);
+IMAQ_FUNC ClassifierReport* IMAQ_STDCALL imaqClassify(Image* image, const ClassifierSession* session, const ROI* roi, double* featureVector, unsigned int vectorSize);
+IMAQ_FUNC ClassifierSession* IMAQ_STDCALL imaqCreateClassifier(ClassifierType type);
+IMAQ_FUNC int IMAQ_STDCALL imaqDeleteClassifierSample(ClassifierSession* session, int index);
+IMAQ_FUNC ClassifierAccuracyReport* IMAQ_STDCALL imaqGetClassifierAccuracy(const ClassifierSession* session);
+IMAQ_FUNC ClassifierSampleInfo* IMAQ_STDCALL imaqGetClassifierSampleInfo(const ClassifierSession* session, int index, int* numSamples);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetColorClassifierOptions(const ClassifierSession* session, ColorOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetNearestNeighborOptions(const ClassifierSession* session, NearestNeighborOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetParticleClassifierOptions2(const ClassifierSession* session, ParticleClassifierPreprocessingOptions2* preprocessingOptions, ParticleClassifierOptions* options);
+IMAQ_FUNC ClassifierSession* IMAQ_STDCALL imaqReadClassifierFile(ClassifierSession* session, const char* fileName, ReadClassifierFileMode mode, ClassifierType* type, ClassifierEngineType* engine, String255 description);
+IMAQ_FUNC int IMAQ_STDCALL imaqRelabelClassifierSample(ClassifierSession* session, int index, const char* newClass);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetParticleClassifierOptions2(ClassifierSession* session, const ParticleClassifierPreprocessingOptions2* preprocessingOptions, const ParticleClassifierOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetColorClassifierOptions(ClassifierSession* session, const ColorOptions* options);
+IMAQ_FUNC NearestNeighborTrainingReport* IMAQ_STDCALL imaqTrainNearestNeighborClassifier(ClassifierSession* session, const NearestNeighborOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteClassifierFile(const ClassifierSession* session, const char* fileName, WriteClassifierFileMode mode, const String255 description);
+
+//============================================================================
+// Measure Distances functions
+//============================================================================
+IMAQ_FUNC ClampMax2Report* IMAQ_STDCALL imaqClampMax2(Image* image, const ROI* roi, const CoordinateSystem* baseSystem, const CoordinateSystem* newSystem, const CurveOptions* curveSettings, const ClampSettings* clampSettings, const ClampOverlaySettings* clampOverlaySettings);
+
+//============================================================================
+// Inspection functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCompareGoldenTemplate(const Image* image, const Image* goldenTemplate, Image* brightDefects, Image* darkDefects, const InspectionAlignment* alignment, const InspectionOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnGoldenTemplate(Image* goldenTemplate, PointFloat originOffset, const Image* mask);
+//============================================================================
+// Obsolete functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqRotate(Image* dest, const Image* source, float angle, PixelValue fill, InterpolationMethod method);
+IMAQ_FUNC int IMAQ_STDCALL imaqWritePNGFile(const Image* image, const char* fileName, unsigned int compressionSpeed, const RGBValue* colorTable);
+IMAQ_FUNC ParticleReport* IMAQ_STDCALL imaqSelectParticles(const Image* image, const ParticleReport* reports, int reportCount, int rejectBorder, const SelectParticleCriteria* criteria, int criteriaCount, int* selectedCount);
+IMAQ_FUNC int IMAQ_STDCALL imaqParticleFilter(Image* dest, Image* source, const ParticleFilterCriteria* criteria, int criteriaCount, int rejectMatches, int connectivity8);
+IMAQ_FUNC ParticleReport* IMAQ_STDCALL imaqGetParticleInfo(Image* image, int connectivity8, ParticleInfoMode mode, int* reportCount);
+IMAQ_FUNC int IMAQ_STDCALL imaqCalcCoeff(const Image* image, const ParticleReport* report, MeasurementValue parameter, float* coefficient);
+IMAQ_FUNC EdgeReport* IMAQ_STDCALL imaqEdgeTool(const Image* image, const Point* points, int numPoints, const EdgeOptions* options, int* numEdges);
+IMAQ_FUNC CircleReport* IMAQ_STDCALL imaqCircles(Image* dest, const Image* source, float minRadius, float maxRadius, int* numCircles);
+IMAQ_FUNC int IMAQ_STDCALL imaqLabel(Image* dest, Image* source, int connectivity8, int* particleCount);
+IMAQ_FUNC int IMAQ_STDCALL imaqFitEllipse(const PointFloat* points, int numPoints, BestEllipse* ellipse);
+IMAQ_FUNC int IMAQ_STDCALL imaqFitCircle(const PointFloat* points, int numPoints, BestCircle* circle);
+IMAQ_FUNC Color IMAQ_STDCALL imaqChangeColorSpace(const Color* sourceColor, ColorMode sourceSpace, ColorMode destSpace);
+IMAQ_FUNC PatternMatch* IMAQ_STDCALL imaqMatchPattern(const Image* image, Image* pattern, const MatchPatternOptions* options, Rect searchRect, int* numMatches);
+IMAQ_FUNC int IMAQ_STDCALL imaqConvex(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqIsVisionInfoPresent(const Image* image, VisionInfoType type, int* present);
+IMAQ_FUNC int IMAQ_STDCALL imaqLineGaugeTool(const Image* image, Point start, Point end, LineGaugeMethod method, const EdgeOptions* edgeOptions, const CoordinateTransform* reference, float* distance);
+IMAQ_FUNC int IMAQ_STDCALL imaqBestCircle(const PointFloat* points, int numPoints, PointFloat* center, double* radius);
+IMAQ_FUNC int IMAQ_STDCALL imaqSavePattern(const Image* pattern, const char* fileName);
+IMAQ_FUNC int IMAQ_STDCALL imaqLoadPattern(Image* pattern, const char* fileName);
+IMAQ_FUNC int IMAQ_STDCALL imaqTransformROI(ROI* roi, Point originStart, float angleStart, Point originFinal, float angleFinal);
+IMAQ_FUNC int IMAQ_STDCALL imaqCoordinateReference(const Point* points, ReferenceMode mode, Point* origin, float* angle);
+IMAQ_FUNC ContourInfo* IMAQ_STDCALL imaqGetContourInfo(const ROI* roi, ContourID id);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowOverlay(int windowNumber, const Overlay* overlay);
+IMAQ_FUNC Overlay* IMAQ_STDCALL imaqCreateOverlayFromROI(const ROI* roi);
+IMAQ_FUNC Overlay* IMAQ_STDCALL imaqCreateOverlayFromMetafile(const void* metafile);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetCalibrationInfo(Image* image, CalibrationUnit unit, float xDistance, float yDistance);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetCalibrationInfo(const Image* image, CalibrationUnit* unit, float* xDistance, float* yDistance);
+IMAQ_FUNC int IMAQ_STDCALL imaqConstructROI(const Image* image, ROI* roi, Tool initialTool, const ToolWindowOptions* tools, const ConstructROIOptions* options, int* okay);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetParticleClassifierOptions(const ClassifierSession* session, ParticleClassifierPreprocessingOptions* preprocessingOptions, ParticleClassifierOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqZoomWindow(int windowNumber, int xZoom, int yZoom, Point center);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetWindowZoom(int windowNumber, int* xZoom, int* yZoom);
+IMAQ_FUNC int IMAQ_STDCALL imaqParticleFilter3(Image* dest, Image* source, const ParticleFilterCriteria2* criteria, int criteriaCount, const ParticleFilterOptions* options, const ROI* roi, int* numParticles);
+IMAQ_FUNC ReadTextReport2* IMAQ_STDCALL imaqReadText2(const Image* image, const CharSet* set, const ROI* roi, const ReadTextOptions* readOptions, const OCRProcessingOptions* processingOptions, const OCRSpacingOptions* spacingOptions);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnPattern2(Image* image, LearningMode learningMode, LearnPatternAdvancedOptions* advancedOptions);
+IMAQ_FUNC int IMAQ_STDCALL imaqConvolve(Image* dest, Image* source, const float* kernel, int matrixRows, int matrixCols, float normalize, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqDivideConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqDivide(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC EdgeReport2* IMAQ_STDCALL imaqEdgeTool3(const Image* image, const ROI* roi, EdgeProcess processType, const EdgeOptions2* edgeOptions);
+IMAQ_FUNC ConcentricRakeReport* IMAQ_STDCALL imaqConcentricRake(const Image* image, const ROI* roi, ConcentricRakeDirection direction, EdgeProcess process, const RakeOptions* options);
+IMAQ_FUNC SpokeReport* IMAQ_STDCALL imaqSpoke(const Image* image, const ROI* roi, SpokeDirection direction, EdgeProcess process, const SpokeOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnPattern(Image* image, LearningMode learningMode);
+IMAQ_FUNC int IMAQ_STDCALL imaqLookup(Image* dest, const Image* source, const short* table, const Image* mask);
+IMAQ_FUNC PatternMatch* IMAQ_STDCALL imaqMatchPattern2(const Image* image, const Image* pattern, const MatchPatternOptions* options, const MatchPatternAdvancedOptions* advancedOptions, Rect searchRect, int* numMatches);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetParticleClassifierOptions(ClassifierSession* session, const ParticleClassifierPreprocessingOptions* preprocessingOptions, const ParticleClassifierOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqCopyCalibrationInfo(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqParticleFilter2(Image* dest, Image* source, const ParticleFilterCriteria2* criteria, int criteriaCount, int rejectMatches, int connectivity8, int* numParticles);
+IMAQ_FUNC EdgeReport* IMAQ_STDCALL imaqEdgeTool2(const Image* image, const Point* points, int numPoints, EdgeProcess process, const EdgeOptions* options, int* numEdges);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddRotatedRectContour(ROI* roi, RotatedRect rect);
+IMAQ_FUNC Barcode2DInfo* IMAQ_STDCALL imaqReadDataMatrixBarcode(const Image* image, const ROI* roi, const DataMatrixOptions* options, unsigned int* numBarcodes);
+IMAQ_FUNC LinearAverages* IMAQ_STDCALL imaqLinearAverages(const Image* image, Rect rect);
+IMAQ_FUNC GeometricPatternMatch* IMAQ_STDCALL imaqMatchGeometricPattern(const Image* image, const Image* pattern, const CurveOptions* curveOptions, const MatchGeometricPatternOptions* matchOptions, const MatchGeometricPatternAdvancedOptions* advancedMatchOptions, const ROI* roi, int* numMatches);
+IMAQ_FUNC CharInfo* IMAQ_STDCALL imaqGetCharInfo(const CharSet* set, int index);
+IMAQ_FUNC ReadTextReport* IMAQ_STDCALL imaqReadText(const Image* image, const CharSet* set, const ROI* roi, const ReadTextOptions* readOptions, const OCRProcessingOptions* processingOptions, const OCRSpacingOptions* spacingOptions);
+IMAQ_FUNC ThresholdData* IMAQ_STDCALL imaqAutoThreshold(Image* dest, Image* source, int numClasses, ThresholdMethod method);
+IMAQ_FUNC ColorHistogramReport* IMAQ_STDCALL imaqColorHistogram(Image* image, int numClasses, ColorMode mode, const Image* mask);
+IMAQ_FUNC RakeReport* IMAQ_STDCALL imaqRake(const Image* image, const ROI* roi, RakeDirection direction, EdgeProcess process, const RakeOptions* options);
+#endif
+
diff --git a/aos/externals/WPILib/WPILib/pcre.h b/aos/externals/WPILib/WPILib/pcre.h
new file mode 100644
index 0000000..f8ddcbf
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/pcre.h
@@ -0,0 +1,338 @@
+/*************************************************
+* Perl-Compatible Regular Expressions *
+*************************************************/
+
+/* This is the public header file for the PCRE library, to be #included by
+applications that call the PCRE functions.
+
+ Copyright (c) 1997-2008 University of Cambridge
+
+-----------------------------------------------------------------------------
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+
+ * Redistributions of source code must retain the above copyright notice,
+ this list of conditions and the following disclaimer.
+
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+
+ * Neither the name of the University of Cambridge nor the names of its
+ contributors may be used to endorse or promote products derived from
+ this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+POSSIBILITY OF SUCH DAMAGE.
+-----------------------------------------------------------------------------
+*/
+
+#ifndef _PCRE_H
+#define _PCRE_H
+
+/* The current PCRE version information. */
+
+#define PCRE_MAJOR 7
+#define PCRE_MINOR 8
+#define PCRE_PRERELEASE
+#define PCRE_DATE 2008-09-05
+
+/* When an application links to a PCRE DLL in Windows, the symbols that are
+imported have to be identified as such. When building PCRE, the appropriate
+export setting is defined in pcre_internal.h, which includes this file. So we
+don't change existing definitions of PCRE_EXP_DECL and PCRECPP_EXP_DECL. */
+
+/**
+ * NI CHANGE
+ *
+ * We don't build the DLL version. We only build the static lib version.
+ * Since we don't want to have to #define PCRE_STATIC in every component that
+ * includes pcre.h, we're just going to go ahead and define it here.
+ *
+ * Adam Kemp, 12/15/2008
+*/
+#define PCRE_STATIC
+
+#if defined(_WIN32) && !defined(PCRE_STATIC)
+# ifndef PCRE_EXP_DECL
+# define PCRE_EXP_DECL extern __declspec(dllimport)
+# endif
+# ifdef __cplusplus
+# ifndef PCRECPP_EXP_DECL
+# define PCRECPP_EXP_DECL extern __declspec(dllimport)
+# endif
+# ifndef PCRECPP_EXP_DEFN
+# define PCRECPP_EXP_DEFN __declspec(dllimport)
+# endif
+# endif
+#endif
+
+/* By default, we use the standard "extern" declarations. */
+
+#ifndef PCRE_EXP_DECL
+# ifdef __cplusplus
+# define PCRE_EXP_DECL extern "C"
+# else
+# define PCRE_EXP_DECL extern
+# endif
+#endif
+
+#ifdef __cplusplus
+# ifndef PCRECPP_EXP_DECL
+# define PCRECPP_EXP_DECL extern
+# endif
+# ifndef PCRECPP_EXP_DEFN
+# define PCRECPP_EXP_DEFN
+# endif
+#endif
+
+/**
+ * NI CHANGE
+ *
+ * We use __cdecl on win32 and the default calling convention elsewhere.
+ *
+ * Originall this macro did not appear in this file, but it was used in
+ * internal headers. I consider it an oversight on the part of the pcre
+ * developers that * it was not used in this file. If these functions use
+ * specific calling conventions then their prototypes should include that
+ * calling convention in case some other project uses a different default.
+ *
+ * Adam Kemp 12/15/2008
+*/
+#ifndef PCRE_CALL_CONVENTION
+# if defined(_WIN32) /* 32-bit and 64-bit */
+# define PCRE_CALL_CONVENTION __cdecl
+# else
+# define PCRE_CALL_CONVENTION
+# endif
+#else
+# define PCRE_CALL_CONVENTION
+#endif
+
+/* Have to include stdlib.h in order to ensure that size_t is defined;
+it is needed here for malloc. */
+
+#include <stdlib.h>
+
+/* Allow for C++ users */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Options */
+
+#define PCRE_CASELESS 0x00000001
+#define PCRE_MULTILINE 0x00000002
+#define PCRE_DOTALL 0x00000004
+#define PCRE_EXTENDED 0x00000008
+#define PCRE_ANCHORED 0x00000010
+#define PCRE_DOLLAR_ENDONLY 0x00000020
+#define PCRE_EXTRA 0x00000040
+#define PCRE_NOTBOL 0x00000080
+#define PCRE_NOTEOL 0x00000100
+#define PCRE_UNGREEDY 0x00000200
+#define PCRE_NOTEMPTY 0x00000400
+#define PCRE_UTF8 0x00000800
+#define PCRE_NO_AUTO_CAPTURE 0x00001000
+#define PCRE_NO_UTF8_CHECK 0x00002000
+#define PCRE_AUTO_CALLOUT 0x00004000
+#define PCRE_PARTIAL 0x00008000
+#define PCRE_DFA_SHORTEST 0x00010000
+#define PCRE_DFA_RESTART 0x00020000
+#define PCRE_FIRSTLINE 0x00040000
+#define PCRE_DUPNAMES 0x00080000
+#define PCRE_NEWLINE_CR 0x00100000
+#define PCRE_NEWLINE_LF 0x00200000
+#define PCRE_NEWLINE_CRLF 0x00300000
+#define PCRE_NEWLINE_ANY 0x00400000
+#define PCRE_NEWLINE_ANYCRLF 0x00500000
+#define PCRE_BSR_ANYCRLF 0x00800000
+#define PCRE_BSR_UNICODE 0x01000000
+#define PCRE_JAVASCRIPT_COMPAT 0x02000000
+
+/* Exec-time and get/set-time error codes */
+
+#define PCRE_ERROR_NOMATCH (-1)
+#define PCRE_ERROR_NULL (-2)
+#define PCRE_ERROR_BADOPTION (-3)
+#define PCRE_ERROR_BADMAGIC (-4)
+#define PCRE_ERROR_UNKNOWN_OPCODE (-5)
+#define PCRE_ERROR_UNKNOWN_NODE (-5) /* For backward compatibility */
+#define PCRE_ERROR_NOMEMORY (-6)
+#define PCRE_ERROR_NOSUBSTRING (-7)
+#define PCRE_ERROR_MATCHLIMIT (-8)
+#define PCRE_ERROR_CALLOUT (-9) /* Never used by PCRE itself */
+#define PCRE_ERROR_BADUTF8 (-10)
+#define PCRE_ERROR_BADUTF8_OFFSET (-11)
+#define PCRE_ERROR_PARTIAL (-12)
+#define PCRE_ERROR_BADPARTIAL (-13)
+#define PCRE_ERROR_INTERNAL (-14)
+#define PCRE_ERROR_BADCOUNT (-15)
+#define PCRE_ERROR_DFA_UITEM (-16)
+#define PCRE_ERROR_DFA_UCOND (-17)
+#define PCRE_ERROR_DFA_UMLIMIT (-18)
+#define PCRE_ERROR_DFA_WSSIZE (-19)
+#define PCRE_ERROR_DFA_RECURSE (-20)
+#define PCRE_ERROR_RECURSIONLIMIT (-21)
+#define PCRE_ERROR_NULLWSLIMIT (-22) /* No longer actually used */
+#define PCRE_ERROR_BADNEWLINE (-23)
+
+/* Request types for pcre_fullinfo() */
+
+#define PCRE_INFO_OPTIONS 0
+#define PCRE_INFO_SIZE 1
+#define PCRE_INFO_CAPTURECOUNT 2
+#define PCRE_INFO_BACKREFMAX 3
+#define PCRE_INFO_FIRSTBYTE 4
+#define PCRE_INFO_FIRSTCHAR 4 /* For backwards compatibility */
+#define PCRE_INFO_FIRSTTABLE 5
+#define PCRE_INFO_LASTLITERAL 6
+#define PCRE_INFO_NAMEENTRYSIZE 7
+#define PCRE_INFO_NAMECOUNT 8
+#define PCRE_INFO_NAMETABLE 9
+#define PCRE_INFO_STUDYSIZE 10
+#define PCRE_INFO_DEFAULT_TABLES 11
+#define PCRE_INFO_OKPARTIAL 12
+#define PCRE_INFO_JCHANGED 13
+#define PCRE_INFO_HASCRORLF 14
+
+/* Request types for pcre_config(). Do not re-arrange, in order to remain
+compatible. */
+
+#define PCRE_CONFIG_UTF8 0
+#define PCRE_CONFIG_NEWLINE 1
+#define PCRE_CONFIG_LINK_SIZE 2
+#define PCRE_CONFIG_POSIX_MALLOC_THRESHOLD 3
+#define PCRE_CONFIG_MATCH_LIMIT 4
+#define PCRE_CONFIG_STACKRECURSE 5
+#define PCRE_CONFIG_UNICODE_PROPERTIES 6
+#define PCRE_CONFIG_MATCH_LIMIT_RECURSION 7
+#define PCRE_CONFIG_BSR 8
+
+/* Bit flags for the pcre_extra structure. Do not re-arrange or redefine
+these bits, just add new ones on the end, in order to remain compatible. */
+
+#define PCRE_EXTRA_STUDY_DATA 0x0001
+#define PCRE_EXTRA_MATCH_LIMIT 0x0002
+#define PCRE_EXTRA_CALLOUT_DATA 0x0004
+#define PCRE_EXTRA_TABLES 0x0008
+#define PCRE_EXTRA_MATCH_LIMIT_RECURSION 0x0010
+
+/* Types */
+
+struct real_pcre; /* declaration; the definition is private */
+typedef struct real_pcre pcre;
+
+/* When PCRE is compiled as a C++ library, the subject pointer type can be
+replaced with a custom type. For conventional use, the public interface is a
+const char *. */
+
+#ifndef PCRE_SPTR
+#define PCRE_SPTR const char *
+#endif
+
+/* The structure for passing additional data to pcre_exec(). This is defined in
+such as way as to be extensible. Always add new fields at the end, in order to
+remain compatible. */
+
+typedef struct pcre_extra {
+ unsigned long int flags; /* Bits for which fields are set */
+ void *study_data; /* Opaque data from pcre_study() */
+ unsigned long int match_limit; /* Maximum number of calls to match() */
+ void *callout_data; /* Data passed back in callouts */
+ const unsigned char *tables; /* Pointer to character tables */
+ unsigned long int match_limit_recursion; /* Max recursive calls to match() */
+} pcre_extra;
+
+/* The structure for passing out data via the pcre_callout_function. We use a
+structure so that new fields can be added on the end in future versions,
+without changing the API of the function, thereby allowing old clients to work
+without modification. */
+
+typedef struct pcre_callout_block {
+ int version; /* Identifies version of block */
+ /* ------------------------ Version 0 ------------------------------- */
+ int callout_number; /* Number compiled into pattern */
+ int *offset_vector; /* The offset vector */
+ PCRE_SPTR subject; /* The subject being matched */
+ int subject_length; /* The length of the subject */
+ int start_match; /* Offset to start of this match attempt */
+ int current_position; /* Where we currently are in the subject */
+ int capture_top; /* Max current capture */
+ int capture_last; /* Most recently closed capture */
+ void *callout_data; /* Data passed in with the call */
+ /* ------------------- Added for Version 1 -------------------------- */
+ int pattern_position; /* Offset to next item in the pattern */
+ int next_item_length; /* Length of next item in the pattern */
+ /* ------------------------------------------------------------------ */
+} pcre_callout_block;
+
+/* Indirection for store get and free functions. These can be set to
+alternative malloc/free functions if required. Special ones are used in the
+non-recursive case for "frames". There is also an optional callout function
+that is triggered by the (?) regex item. For Virtual Pascal, these definitions
+have to take another form. */
+
+#ifndef VPCOMPAT
+PCRE_EXP_DECL void* (PCRE_CALL_CONVENTION *pcre_malloc)(size_t);
+PCRE_EXP_DECL void (PCRE_CALL_CONVENTION *pcre_free)(void *);
+PCRE_EXP_DECL void* (PCRE_CALL_CONVENTION *pcre_stack_malloc)(size_t);
+PCRE_EXP_DECL void (PCRE_CALL_CONVENTION *pcre_stack_free)(void *);
+PCRE_EXP_DECL int (PCRE_CALL_CONVENTION *pcre_callout)(pcre_callout_block *);
+#else /* VPCOMPAT */
+PCRE_EXP_DECL void* PCRE_CALL_CONVENTION pcre_malloc(size_t);
+PCRE_EXP_DECL void PCRE_CALL_CONVENTION pcre_free(void *);
+PCRE_EXP_DECL void* PCRE_CALL_CONVENTION pcre_stack_malloc(size_t);
+PCRE_EXP_DECL void PCRE_CALL_CONVENTION pcre_stack_free(void *);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_callout(pcre_callout_block *);
+#endif /* VPCOMPAT */
+
+/* Exported PCRE functions */
+
+PCRE_EXP_DECL pcre* PCRE_CALL_CONVENTION pcre_compile(const char *, int, const char **, int *,
+ const unsigned char *);
+PCRE_EXP_DECL pcre* PCRE_CALL_CONVENTION pcre_compile2(const char *, int, int *, const char **,
+ int *, const unsigned char *);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_config(int, void *);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_copy_named_substring(const pcre *, const char *,
+ int *, int, const char *, char *, int);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_copy_substring(const char *, int *, int, int, char *,
+ int);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_dfa_exec(const pcre *, const pcre_extra *,
+ const char *, int, int, int, int *, int , int *, int);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_exec(const pcre *, const pcre_extra *, PCRE_SPTR,
+ int, int, int, int *, int);
+PCRE_EXP_DECL void PCRE_CALL_CONVENTION pcre_free_substring(const char *);
+PCRE_EXP_DECL void PCRE_CALL_CONVENTION pcre_free_substring_list(const char **);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_fullinfo(const pcre *, const pcre_extra *, int,
+ void *);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_get_named_substring(const pcre *, const char *,
+ int *, int, const char *, const char **);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_get_stringnumber(const pcre *, const char *);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_get_stringtable_entries(const pcre *, const char *,
+ char **, char **);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_get_substring(const char *, int *, int, int,
+ const char **);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_get_substring_list(const char *, int *, int,
+ const char ***);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_info(const pcre *, int *, int *);
+PCRE_EXP_DECL const unsigned char* PCRE_CALL_CONVENTION pcre_maketables(void);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_refcount(pcre *, int);
+PCRE_EXP_DECL pcre_extra* PCRE_CALL_CONVENTION pcre_study(const pcre *, int, const char **);
+PCRE_EXP_DECL const char* PCRE_CALL_CONVENTION pcre_version(void);
+
+#ifdef __cplusplus
+} /* extern "C" */
+#endif
+
+#endif /* End of pcre.h */
diff --git a/aos/externals/WPILib/WPILib/visa/Makefile b/aos/externals/WPILib/WPILib/visa/Makefile
new file mode 100644
index 0000000..bc19164
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/visa/Makefile
@@ -0,0 +1,2184 @@
+# Wind River Workbench generated Makefile.
+# Do not edit!!!
+#
+# The file ".wrmakefile" is the template used by the Wind River Workbench to
+# generate the makefiles of this project. Add user-specific build targets and
+# make rules only(!) in this project's ".wrmakefile" file. These will then be
+# automatically dumped into the makefiles.
+
+WIND_HOME := $(subst \,/,$(WIND_HOME))
+WIND_BASE := $(subst \,/,$(WIND_BASE))
+WIND_USR := $(subst \,/,$(WIND_USR))
+
+all : pre_build main_all post_build
+
+_clean ::
+ @echo "make: removing targets and objects of `pwd`"
+
+TRACE=0
+TRACEON=$(TRACE:0=@)
+TRACE_FLAG=$(TRACEON:1=)
+
+MAKEFILE := Makefile
+
+BUILD_SPEC = PPC603gnu
+DEBUG_MODE = 1
+SRC_DIR := .
+BUILD_ROOT_DIR :=
+PRJ_ROOT_DIR := C:/windriver/workspace/WPILib
+WS_ROOT_DIR := C:/windriver/workspace
+
+ALL_BUILD_SPECS := PPC32diab PPC32gnu PPC32sfdiab PPC32sfgnu \
+ PPC403diab PPC403gnu PPC405diab PPC405gnu \
+ PPC405sfdiab PPC405sfgnu PPC440diab PPC440gnu \
+ PPC440sfdiab PPC440sfgnu PPC603diab PPC603gnu \
+ PPC604diab PPC604gnu PPC85XXdiab PPC85XXgnu \
+ PPC85XXsfdiab PPC85XXsfgnu PPC860sfdiab PPC860sfgnu \
+ SIMLINUXdiab SIMLINUXgnu SIMNTdiab SIMNTgnu \
+ SIMSPARCSOLARISdiab SIMSPARCSOLARISgnu
+ENABLED_BUILD_SPECS := PPC603gnu
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32diab_DEBUG
+else
+OBJ_DIR := PPC32diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32gnu_DEBUG
+else
+OBJ_DIR := PPC32gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfdiab_DEBUG
+else
+OBJ_DIR := PPC32sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC32sfgnu_DEBUG
+else
+OBJ_DIR := PPC32sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403diab_DEBUG
+else
+OBJ_DIR := PPC403diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC403gnu_DEBUG
+else
+OBJ_DIR := PPC403gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405diab_DEBUG
+else
+OBJ_DIR := PPC405diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405gnu_DEBUG
+else
+OBJ_DIR := PPC405gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfdiab_DEBUG
+else
+OBJ_DIR := PPC405sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC405sfgnu_DEBUG
+else
+OBJ_DIR := PPC405sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440diab_DEBUG
+else
+OBJ_DIR := PPC440diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440gnu_DEBUG
+else
+OBJ_DIR := PPC440gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfdiab_DEBUG
+else
+OBJ_DIR := PPC440sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC440sfgnu_DEBUG
+else
+OBJ_DIR := PPC440sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603diab_DEBUG
+else
+OBJ_DIR := PPC603diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC603gnu_DEBUG
+else
+OBJ_DIR := PPC603gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604diab_DEBUG
+else
+OBJ_DIR := PPC604diab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC604gnu_DEBUG
+else
+OBJ_DIR := PPC604gnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXdiab_DEBUG
+else
+OBJ_DIR := PPC85XXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXgnu_DEBUG
+else
+OBJ_DIR := PPC85XXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfdiab_DEBUG
+else
+OBJ_DIR := PPC85XXsfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC85XXsfgnu_DEBUG
+else
+OBJ_DIR := PPC85XXsfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfdiab_DEBUG
+else
+OBJ_DIR := PPC860sfdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := PPC860sfgnu_DEBUG
+else
+OBJ_DIR := PPC860sfgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXdiab_DEBUG
+else
+OBJ_DIR := SIMLINUXdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMLINUXgnu_DEBUG
+else
+OBJ_DIR := SIMLINUXgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTdiab_DEBUG
+else
+OBJ_DIR := SIMNTdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMNTgnu_DEBUG
+else
+OBJ_DIR := SIMNTgnu
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISdiab_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISdiab
+endif
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+OBJ_DIR := SIMSPARCSOLARISgnu_DEBUG
+else
+OBJ_DIR := SIMSPARCSOLARISgnu
+endif
+endif
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+SUBDIRS :=
+OBJECTS :=
+
+PROJECT_TARGETS := $(OBJECTS)
+
+SUB_OBJECTS :=
+SUB_TARGETS :=
+endif
+
+PROJECT_TYPE = DKM
+DEFINES =
+EXPAND_DBG = 0
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFH:vxworks63 -Xstmw-slow -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mhard-float -mstrict-align -mno-implicit-fp -DPPC32_fp60x
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCFS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC32
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -msoft-float -mstrict-align
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC403FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC403gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC403
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=403 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC405FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC405
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=405 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC440FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC440
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=440 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC603FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC603gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC603
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=603 -mstrict-align -mno-implicit-fp -mlongcall
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I.. -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604diab)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC604FH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC604gnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC604
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=604 -mstrict-align -mno-implicit-fp
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPCE500FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC85XX
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=8540 -mstrict-align -msoft-float -mabi=no-spe
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = diab
+TOOL = sfdiab
+TOOL_PATH =
+CC_ARCH_SPEC = -tPPC860FS:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+VX_CPU_FAMILY = ppc
+CPU = PPC860
+TOOL_FAMILY = gnu
+TOOL = sfgnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mcpu=860 -mstrict-align -msoft-float
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+VX_CPU_FAMILY = simlinux
+CPU = SIMLINUX
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tX86LH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+VX_CPU_FAMILY = simpc
+CPU = SIMNT
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC = -mtune=i486 -march=i486
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = diab
+TOOL = diab
+TOOL_PATH =
+CC_ARCH_SPEC = -tSPARCFH:vxworks63
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+VX_CPU_FAMILY = simso
+CPU = SIMSPARCSOLARIS
+TOOL_FAMILY = gnu
+TOOL = gnu
+TOOL_PATH =
+CC_ARCH_SPEC =
+LIBPATH =
+LIBS =
+
+IDE_INCLUDES = -I$(WIND_BASE)/target/h -I$(WIND_BASE)/target/h/wrn/coreip
+
+IDE_LIBRARIES =
+endif
+
+
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C-Compiler = -g
+else
+DEBUGFLAGS_C-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.c
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG) $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL -D'SVN_REV="$(shell svnversion -n ..)"' $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xforce-declarations -Xmake-dependency=0xd $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_C++-Compiler = -g
+else
+DEBUGFLAGS_C++-Compiler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cpp
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.C
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cxx
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.cc
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_C++-Compiler) $(CC_ARCH_SPEC) -ansi -Wall -MD -MP $(ADDED_C++FLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xstsw-slow -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC32sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC403gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC405sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC440sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC603gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604diab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC604gnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC85XXsfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),PPC860sfgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccppc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMLINUXgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Wa,-Xmnem-mit -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMNTgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -nostdlib -fno-builtin -fno-defer-pop
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccpentium $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISdiab)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -XO -Xsize-opt
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)dcc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -W:c:,-Xclib-optim-off -Xansi -Xlocal-data-area-static-only -Xpreprocess-assembly -Xcpp-no-space -Xmake-dependency=0xd $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+ifeq ($(BUILD_SPEC),SIMSPARCSOLARISgnu)
+ifeq ($(DEBUG_MODE),1)
+DEBUGFLAGS_Assembler = -g
+else
+DEBUGFLAGS_Assembler = -O2 -fstrength-reduce -fno-builtin
+endif
+$(OBJ_DIR)/%.o : $(SRC_DIR)/%.s
+ $(TRACE_FLAG)echo "building $@"; $(TOOL_PATH)ccsparc $(DEBUGFLAGS_Assembler) $(CC_ARCH_SPEC) -ansi -xassembler-with-cpp -MD -MP $(ADDED_CFLAGS) $(IDE_INCLUDES) $(ADDED_INCLUDES) -DCPU=$(CPU) -DTOOL_FAMILY=$(TOOL_FAMILY) -DTOOL=$(TOOL) -D_WRS_KERNEL $(DEFINES) -o "$@" -c "$<"
+
+endif
+
+
+
+
+
+-include $(PRJ_ROOT_DIR)/*.makefile
+
+-include *.makefile
+
+main_all : external_build $(PROJECT_TARGETS)
+ @echo "make: built targets of `pwd`"
+
+# entry point for extending the build
+external_build ::
+ @echo ""
+
+# main entry point for pre processing prior to the build
+pre_build :: $(PRE_BUILD_STEP) generate_sources
+ @echo ""
+
+# entry point for generating sources prior to the build
+generate_sources ::
+ @echo ""
+
+# main entry point for post processing after the build
+post_build :: $(POST_BUILD_STEP) deploy_output
+ @echo ""
+
+# entry point for deploying output after the build
+deploy_output ::
+ @echo ""
+
+clean :: external_clean $(CLEAN_STEP) _clean
+
+# entry point for extending the build clean
+external_clean ::
+ @echo ""
diff --git a/aos/externals/WPILib/WPILib/visa/visa.h b/aos/externals/WPILib/WPILib/visa/visa.h
new file mode 100644
index 0000000..3c6ad30
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/visa/visa.h
@@ -0,0 +1,1064 @@
+/*---------------------------------------------------------------------------*/
+/* Distributed by IVI Foundation Inc. */
+/* Contains National Instruments extensions. */
+/* Do not modify the contents of this file. */
+/*---------------------------------------------------------------------------*/
+/* */
+/* Title : VISA.H */
+/* Date : 10-09-2006 */
+/* Purpose : Include file for the VISA Library 4.0 specification */
+/* */
+/*---------------------------------------------------------------------------*/
+/* When using NI-VISA extensions, you must link with the VISA library that */
+/* comes with NI-VISA. Currently, the extensions provided by NI-VISA are: */
+/* */
+/* PXI (Compact PCI eXtensions for Instrumentation) and PCI support. To use */
+/* this, you must define the macro NIVISA_PXI before including this header. */
+/* You must also create an INF file with the VISA Driver Development Wizard. */
+/* */
+/* A fast set of macros for viPeekXX/viPokeXX that guarantees binary */
+/* compatibility with other implementations of VISA. To use this, you must */
+/* define the macro NIVISA_PEEKPOKE before including this header. */
+/* */
+/* Support for USB devices that do not conform to a specific class. To use */
+/* this, you must define the macro NIVISA_USB before including this header. */
+/* You must also create an INF file with the VISA Driver Development Wizard. */
+/*---------------------------------------------------------------------------*/
+
+#ifndef __VISA_HEADER__
+#define __VISA_HEADER__
+
+#include <stdarg.h>
+
+#if !defined(__VISATYPE_HEADER__)
+#include "visatype.h"
+#endif
+
+#define VI_SPEC_VERSION (0x00400000UL)
+
+#if defined(__cplusplus) || defined(__cplusplus__)
+ extern "C" {
+#endif
+
+#if defined(_CVI_)
+#pragma EnableLibraryRuntimeChecking
+#endif
+
+/*- VISA Types --------------------------------------------------------------*/
+
+typedef ViObject ViEvent;
+typedef ViEvent _VI_PTR ViPEvent;
+typedef ViObject ViFindList;
+typedef ViFindList _VI_PTR ViPFindList;
+
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+typedef ViUInt64 ViBusAddress;
+typedef ViUInt64 ViBusSize;
+typedef ViUInt64 ViAttrState;
+#else
+typedef ViUInt32 ViBusAddress;
+typedef ViUInt32 ViBusSize;
+typedef ViUInt32 ViAttrState;
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+typedef ViUInt64 ViBusAddress64;
+typedef ViBusAddress64 _VI_PTR ViPBusAddress64;
+#endif
+
+typedef ViUInt32 ViEventType;
+typedef ViEventType _VI_PTR ViPEventType;
+typedef ViEventType _VI_PTR ViAEventType;
+typedef void _VI_PTR ViPAttrState;
+typedef ViAttr _VI_PTR ViPAttr;
+typedef ViAttr _VI_PTR ViAAttr;
+
+typedef ViString ViKeyId;
+typedef ViPString ViPKeyId;
+typedef ViUInt32 ViJobId;
+typedef ViJobId _VI_PTR ViPJobId;
+typedef ViUInt32 ViAccessMode;
+typedef ViAccessMode _VI_PTR ViPAccessMode;
+typedef ViBusAddress _VI_PTR ViPBusAddress;
+typedef ViUInt32 ViEventFilter;
+
+typedef va_list ViVAList;
+
+typedef ViStatus (_VI_FUNCH _VI_PTR ViHndlr)
+ (ViSession vi, ViEventType eventType, ViEvent event, ViAddr userHandle);
+
+/*- Resource Manager Functions and Operations -------------------------------*/
+
+ViStatus _VI_FUNC viOpenDefaultRM (ViPSession vi);
+ViStatus _VI_FUNC viFindRsrc (ViSession sesn, ViString expr, ViPFindList vi,
+ ViPUInt32 retCnt, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC viFindNext (ViFindList vi, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC viParseRsrc (ViSession rmSesn, ViRsrc rsrcName,
+ ViPUInt16 intfType, ViPUInt16 intfNum);
+ViStatus _VI_FUNC viParseRsrcEx (ViSession rmSesn, ViRsrc rsrcName, ViPUInt16 intfType,
+ ViPUInt16 intfNum, ViChar _VI_FAR rsrcClass[],
+ ViChar _VI_FAR expandedUnaliasedName[],
+ ViChar _VI_FAR aliasIfExists[]);
+ViStatus _VI_FUNC viOpen (ViSession sesn, ViRsrc name, ViAccessMode mode,
+ ViUInt32 timeout, ViPSession vi);
+
+/*- Resource Template Operations --------------------------------------------*/
+
+ViStatus _VI_FUNC viClose (ViObject vi);
+ViStatus _VI_FUNC viSetAttribute (ViObject vi, ViAttr attrName, ViAttrState attrValue);
+ViStatus _VI_FUNC viGetAttribute (ViObject vi, ViAttr attrName, void _VI_PTR attrValue);
+ViStatus _VI_FUNC viStatusDesc (ViObject vi, ViStatus status, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC viTerminate (ViObject vi, ViUInt16 degree, ViJobId jobId);
+
+ViStatus _VI_FUNC viLock (ViSession vi, ViAccessMode lockType, ViUInt32 timeout,
+ ViKeyId requestedKey, ViChar _VI_FAR accessKey[]);
+ViStatus _VI_FUNC viUnlock (ViSession vi);
+ViStatus _VI_FUNC viEnableEvent (ViSession vi, ViEventType eventType, ViUInt16 mechanism,
+ ViEventFilter context);
+ViStatus _VI_FUNC viDisableEvent (ViSession vi, ViEventType eventType, ViUInt16 mechanism);
+ViStatus _VI_FUNC viDiscardEvents (ViSession vi, ViEventType eventType, ViUInt16 mechanism);
+ViStatus _VI_FUNC viWaitOnEvent (ViSession vi, ViEventType inEventType, ViUInt32 timeout,
+ ViPEventType outEventType, ViPEvent outContext);
+ViStatus _VI_FUNC viInstallHandler(ViSession vi, ViEventType eventType, ViHndlr handler,
+ ViAddr userHandle);
+ViStatus _VI_FUNC viUninstallHandler(ViSession vi, ViEventType eventType, ViHndlr handler,
+ ViAddr userHandle);
+
+/*- Basic I/O Operations ----------------------------------------------------*/
+
+ViStatus _VI_FUNC viRead (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC viReadAsync (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPJobId jobId);
+ViStatus _VI_FUNC viReadToFile (ViSession vi, ViConstString filename, ViUInt32 cnt,
+ ViPUInt32 retCnt);
+ViStatus _VI_FUNC viWrite (ViSession vi, ViBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC viWriteAsync (ViSession vi, ViBuf buf, ViUInt32 cnt, ViPJobId jobId);
+ViStatus _VI_FUNC viWriteFromFile (ViSession vi, ViConstString filename, ViUInt32 cnt,
+ ViPUInt32 retCnt);
+ViStatus _VI_FUNC viAssertTrigger (ViSession vi, ViUInt16 protocol);
+ViStatus _VI_FUNC viReadSTB (ViSession vi, ViPUInt16 status);
+ViStatus _VI_FUNC viClear (ViSession vi);
+
+/*- Formatted and Buffered I/O Operations -----------------------------------*/
+
+ViStatus _VI_FUNC viSetBuf (ViSession vi, ViUInt16 mask, ViUInt32 size);
+ViStatus _VI_FUNC viFlush (ViSession vi, ViUInt16 mask);
+
+ViStatus _VI_FUNC viBufWrite (ViSession vi, ViBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC viBufRead (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+
+ViStatus _VI_FUNCC viPrintf (ViSession vi, ViString writeFmt, ...);
+ViStatus _VI_FUNC viVPrintf (ViSession vi, ViString writeFmt, ViVAList params);
+ViStatus _VI_FUNCC viSPrintf (ViSession vi, ViPBuf buf, ViString writeFmt, ...);
+ViStatus _VI_FUNC viVSPrintf (ViSession vi, ViPBuf buf, ViString writeFmt,
+ ViVAList parms);
+
+ViStatus _VI_FUNCC viScanf (ViSession vi, ViString readFmt, ...);
+ViStatus _VI_FUNC viVScanf (ViSession vi, ViString readFmt, ViVAList params);
+ViStatus _VI_FUNCC viSScanf (ViSession vi, ViBuf buf, ViString readFmt, ...);
+ViStatus _VI_FUNC viVSScanf (ViSession vi, ViBuf buf, ViString readFmt,
+ ViVAList parms);
+
+ViStatus _VI_FUNCC viQueryf (ViSession vi, ViString writeFmt, ViString readFmt, ...);
+ViStatus _VI_FUNC viVQueryf (ViSession vi, ViString writeFmt, ViString readFmt,
+ ViVAList params);
+
+/*- Memory I/O Operations ---------------------------------------------------*/
+
+ViStatus _VI_FUNC viIn8 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViPUInt8 val8);
+ViStatus _VI_FUNC viOut8 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViUInt8 val8);
+ViStatus _VI_FUNC viIn16 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViPUInt16 val16);
+ViStatus _VI_FUNC viOut16 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViUInt16 val16);
+ViStatus _VI_FUNC viIn32 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViPUInt32 val32);
+ViStatus _VI_FUNC viOut32 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViUInt32 val32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC viIn64 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViPUInt64 val64);
+ViStatus _VI_FUNC viOut64 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViUInt64 val64);
+
+ViStatus _VI_FUNC viIn8Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViPUInt8 val8);
+ViStatus _VI_FUNC viOut8Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViUInt8 val8);
+ViStatus _VI_FUNC viIn16Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViPUInt16 val16);
+ViStatus _VI_FUNC viOut16Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViUInt16 val16);
+ViStatus _VI_FUNC viIn32Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViPUInt32 val32);
+ViStatus _VI_FUNC viOut32Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViUInt32 val32);
+ViStatus _VI_FUNC viIn64Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViPUInt64 val64);
+ViStatus _VI_FUNC viOut64Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViUInt64 val64);
+#endif
+
+ViStatus _VI_FUNC viMoveIn8 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt8 buf8);
+ViStatus _VI_FUNC viMoveOut8 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt8 buf8);
+ViStatus _VI_FUNC viMoveIn16 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC viMoveOut16 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC viMoveIn32 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC viMoveOut32 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt32 buf32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC viMoveIn64 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt64 buf64);
+ViStatus _VI_FUNC viMoveOut64 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt64 buf64);
+
+ViStatus _VI_FUNC viMoveIn8Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt8 buf8);
+ViStatus _VI_FUNC viMoveOut8Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt8 buf8);
+ViStatus _VI_FUNC viMoveIn16Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC viMoveOut16Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC viMoveIn32Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC viMoveOut32Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC viMoveIn64Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt64 buf64);
+ViStatus _VI_FUNC viMoveOut64Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt64 buf64);
+#endif
+
+ViStatus _VI_FUNC viMove (ViSession vi, ViUInt16 srcSpace, ViBusAddress srcOffset,
+ ViUInt16 srcWidth, ViUInt16 destSpace,
+ ViBusAddress destOffset, ViUInt16 destWidth,
+ ViBusSize srcLength);
+ViStatus _VI_FUNC viMoveAsync (ViSession vi, ViUInt16 srcSpace, ViBusAddress srcOffset,
+ ViUInt16 srcWidth, ViUInt16 destSpace,
+ ViBusAddress destOffset, ViUInt16 destWidth,
+ ViBusSize srcLength, ViPJobId jobId);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC viMoveEx (ViSession vi, ViUInt16 srcSpace, ViBusAddress64 srcOffset,
+ ViUInt16 srcWidth, ViUInt16 destSpace,
+ ViBusAddress64 destOffset, ViUInt16 destWidth,
+ ViBusSize srcLength);
+ViStatus _VI_FUNC viMoveAsyncEx (ViSession vi, ViUInt16 srcSpace, ViBusAddress64 srcOffset,
+ ViUInt16 srcWidth, ViUInt16 destSpace,
+ ViBusAddress64 destOffset, ViUInt16 destWidth,
+ ViBusSize srcLength, ViPJobId jobId);
+#endif
+
+ViStatus _VI_FUNC viMapAddress (ViSession vi, ViUInt16 mapSpace, ViBusAddress mapOffset,
+ ViBusSize mapSize, ViBoolean access,
+ ViAddr suggested, ViPAddr address);
+ViStatus _VI_FUNC viUnmapAddress (ViSession vi);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC viMapAddressEx (ViSession vi, ViUInt16 mapSpace, ViBusAddress64 mapOffset,
+ ViBusSize mapSize, ViBoolean access,
+ ViAddr suggested, ViPAddr address);
+#endif
+
+void _VI_FUNC viPeek8 (ViSession vi, ViAddr address, ViPUInt8 val8);
+void _VI_FUNC viPoke8 (ViSession vi, ViAddr address, ViUInt8 val8);
+void _VI_FUNC viPeek16 (ViSession vi, ViAddr address, ViPUInt16 val16);
+void _VI_FUNC viPoke16 (ViSession vi, ViAddr address, ViUInt16 val16);
+void _VI_FUNC viPeek32 (ViSession vi, ViAddr address, ViPUInt32 val32);
+void _VI_FUNC viPoke32 (ViSession vi, ViAddr address, ViUInt32 val32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+void _VI_FUNC viPeek64 (ViSession vi, ViAddr address, ViPUInt64 val64);
+void _VI_FUNC viPoke64 (ViSession vi, ViAddr address, ViUInt64 val64);
+#endif
+
+/*- Shared Memory Operations ------------------------------------------------*/
+
+ViStatus _VI_FUNC viMemAlloc (ViSession vi, ViBusSize size, ViPBusAddress offset);
+ViStatus _VI_FUNC viMemFree (ViSession vi, ViBusAddress offset);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC viMemAllocEx (ViSession vi, ViBusSize size, ViPBusAddress64 offset);
+ViStatus _VI_FUNC viMemFreeEx (ViSession vi, ViBusAddress64 offset);
+#endif
+
+/*- Interface Specific Operations -------------------------------------------*/
+
+ViStatus _VI_FUNC viGpibControlREN(ViSession vi, ViUInt16 mode);
+ViStatus _VI_FUNC viGpibControlATN(ViSession vi, ViUInt16 mode);
+ViStatus _VI_FUNC viGpibSendIFC (ViSession vi);
+ViStatus _VI_FUNC viGpibCommand (ViSession vi, ViBuf cmd, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC viGpibPassControl(ViSession vi, ViUInt16 primAddr, ViUInt16 secAddr);
+
+ViStatus _VI_FUNC viVxiCommandQuery(ViSession vi, ViUInt16 mode, ViUInt32 cmd,
+ ViPUInt32 response);
+ViStatus _VI_FUNC viAssertUtilSignal(ViSession vi, ViUInt16 line);
+ViStatus _VI_FUNC viAssertIntrSignal(ViSession vi, ViInt16 mode, ViUInt32 statusID);
+ViStatus _VI_FUNC viMapTrigger (ViSession vi, ViInt16 trigSrc, ViInt16 trigDest,
+ ViUInt16 mode);
+ViStatus _VI_FUNC viUnmapTrigger (ViSession vi, ViInt16 trigSrc, ViInt16 trigDest);
+ViStatus _VI_FUNC viUsbControlOut (ViSession vi, ViInt16 bmRequestType, ViInt16 bRequest,
+ ViUInt16 wValue, ViUInt16 wIndex, ViUInt16 wLength,
+ ViBuf buf);
+ViStatus _VI_FUNC viUsbControlIn (ViSession vi, ViInt16 bmRequestType, ViInt16 bRequest,
+ ViUInt16 wValue, ViUInt16 wIndex, ViUInt16 wLength,
+ ViPBuf buf, ViPUInt16 retCnt);
+
+/*- Attributes (platform independent size) ----------------------------------*/
+
+#define VI_ATTR_RSRC_CLASS (0xBFFF0001UL)
+#define VI_ATTR_RSRC_NAME (0xBFFF0002UL)
+#define VI_ATTR_RSRC_IMPL_VERSION (0x3FFF0003UL)
+#define VI_ATTR_RSRC_LOCK_STATE (0x3FFF0004UL)
+#define VI_ATTR_MAX_QUEUE_LENGTH (0x3FFF0005UL)
+#define VI_ATTR_USER_DATA_32 (0x3FFF0007UL)
+#define VI_ATTR_FDC_CHNL (0x3FFF000DUL)
+#define VI_ATTR_FDC_MODE (0x3FFF000FUL)
+#define VI_ATTR_FDC_GEN_SIGNAL_EN (0x3FFF0011UL)
+#define VI_ATTR_FDC_USE_PAIR (0x3FFF0013UL)
+#define VI_ATTR_SEND_END_EN (0x3FFF0016UL)
+#define VI_ATTR_TERMCHAR (0x3FFF0018UL)
+#define VI_ATTR_TMO_VALUE (0x3FFF001AUL)
+#define VI_ATTR_GPIB_READDR_EN (0x3FFF001BUL)
+#define VI_ATTR_IO_PROT (0x3FFF001CUL)
+#define VI_ATTR_DMA_ALLOW_EN (0x3FFF001EUL)
+#define VI_ATTR_ASRL_BAUD (0x3FFF0021UL)
+#define VI_ATTR_ASRL_DATA_BITS (0x3FFF0022UL)
+#define VI_ATTR_ASRL_PARITY (0x3FFF0023UL)
+#define VI_ATTR_ASRL_STOP_BITS (0x3FFF0024UL)
+#define VI_ATTR_ASRL_FLOW_CNTRL (0x3FFF0025UL)
+#define VI_ATTR_RD_BUF_OPER_MODE (0x3FFF002AUL)
+#define VI_ATTR_RD_BUF_SIZE (0x3FFF002BUL)
+#define VI_ATTR_WR_BUF_OPER_MODE (0x3FFF002DUL)
+#define VI_ATTR_WR_BUF_SIZE (0x3FFF002EUL)
+#define VI_ATTR_SUPPRESS_END_EN (0x3FFF0036UL)
+#define VI_ATTR_TERMCHAR_EN (0x3FFF0038UL)
+#define VI_ATTR_DEST_ACCESS_PRIV (0x3FFF0039UL)
+#define VI_ATTR_DEST_BYTE_ORDER (0x3FFF003AUL)
+#define VI_ATTR_SRC_ACCESS_PRIV (0x3FFF003CUL)
+#define VI_ATTR_SRC_BYTE_ORDER (0x3FFF003DUL)
+#define VI_ATTR_SRC_INCREMENT (0x3FFF0040UL)
+#define VI_ATTR_DEST_INCREMENT (0x3FFF0041UL)
+#define VI_ATTR_WIN_ACCESS_PRIV (0x3FFF0045UL)
+#define VI_ATTR_WIN_BYTE_ORDER (0x3FFF0047UL)
+#define VI_ATTR_GPIB_ATN_STATE (0x3FFF0057UL)
+#define VI_ATTR_GPIB_ADDR_STATE (0x3FFF005CUL)
+#define VI_ATTR_GPIB_CIC_STATE (0x3FFF005EUL)
+#define VI_ATTR_GPIB_NDAC_STATE (0x3FFF0062UL)
+#define VI_ATTR_GPIB_SRQ_STATE (0x3FFF0067UL)
+#define VI_ATTR_GPIB_SYS_CNTRL_STATE (0x3FFF0068UL)
+#define VI_ATTR_GPIB_HS488_CBL_LEN (0x3FFF0069UL)
+#define VI_ATTR_CMDR_LA (0x3FFF006BUL)
+#define VI_ATTR_VXI_DEV_CLASS (0x3FFF006CUL)
+#define VI_ATTR_MAINFRAME_LA (0x3FFF0070UL)
+#define VI_ATTR_MANF_NAME (0xBFFF0072UL)
+#define VI_ATTR_MODEL_NAME (0xBFFF0077UL)
+#define VI_ATTR_VXI_VME_INTR_STATUS (0x3FFF008BUL)
+#define VI_ATTR_VXI_TRIG_STATUS (0x3FFF008DUL)
+#define VI_ATTR_VXI_VME_SYSFAIL_STATE (0x3FFF0094UL)
+#define VI_ATTR_WIN_BASE_ADDR_32 (0x3FFF0098UL)
+#define VI_ATTR_WIN_SIZE_32 (0x3FFF009AUL)
+#define VI_ATTR_ASRL_AVAIL_NUM (0x3FFF00ACUL)
+#define VI_ATTR_MEM_BASE_32 (0x3FFF00ADUL)
+#define VI_ATTR_ASRL_CTS_STATE (0x3FFF00AEUL)
+#define VI_ATTR_ASRL_DCD_STATE (0x3FFF00AFUL)
+#define VI_ATTR_ASRL_DSR_STATE (0x3FFF00B1UL)
+#define VI_ATTR_ASRL_DTR_STATE (0x3FFF00B2UL)
+#define VI_ATTR_ASRL_END_IN (0x3FFF00B3UL)
+#define VI_ATTR_ASRL_END_OUT (0x3FFF00B4UL)
+#define VI_ATTR_ASRL_REPLACE_CHAR (0x3FFF00BEUL)
+#define VI_ATTR_ASRL_RI_STATE (0x3FFF00BFUL)
+#define VI_ATTR_ASRL_RTS_STATE (0x3FFF00C0UL)
+#define VI_ATTR_ASRL_XON_CHAR (0x3FFF00C1UL)
+#define VI_ATTR_ASRL_XOFF_CHAR (0x3FFF00C2UL)
+#define VI_ATTR_WIN_ACCESS (0x3FFF00C3UL)
+#define VI_ATTR_RM_SESSION (0x3FFF00C4UL)
+#define VI_ATTR_VXI_LA (0x3FFF00D5UL)
+#define VI_ATTR_MANF_ID (0x3FFF00D9UL)
+#define VI_ATTR_MEM_SIZE_32 (0x3FFF00DDUL)
+#define VI_ATTR_MEM_SPACE (0x3FFF00DEUL)
+#define VI_ATTR_MODEL_CODE (0x3FFF00DFUL)
+#define VI_ATTR_SLOT (0x3FFF00E8UL)
+#define VI_ATTR_INTF_INST_NAME (0xBFFF00E9UL)
+#define VI_ATTR_IMMEDIATE_SERV (0x3FFF0100UL)
+#define VI_ATTR_INTF_PARENT_NUM (0x3FFF0101UL)
+#define VI_ATTR_RSRC_SPEC_VERSION (0x3FFF0170UL)
+#define VI_ATTR_INTF_TYPE (0x3FFF0171UL)
+#define VI_ATTR_GPIB_PRIMARY_ADDR (0x3FFF0172UL)
+#define VI_ATTR_GPIB_SECONDARY_ADDR (0x3FFF0173UL)
+#define VI_ATTR_RSRC_MANF_NAME (0xBFFF0174UL)
+#define VI_ATTR_RSRC_MANF_ID (0x3FFF0175UL)
+#define VI_ATTR_INTF_NUM (0x3FFF0176UL)
+#define VI_ATTR_TRIG_ID (0x3FFF0177UL)
+#define VI_ATTR_GPIB_REN_STATE (0x3FFF0181UL)
+#define VI_ATTR_GPIB_UNADDR_EN (0x3FFF0184UL)
+#define VI_ATTR_DEV_STATUS_BYTE (0x3FFF0189UL)
+#define VI_ATTR_FILE_APPEND_EN (0x3FFF0192UL)
+#define VI_ATTR_VXI_TRIG_SUPPORT (0x3FFF0194UL)
+#define VI_ATTR_TCPIP_ADDR (0xBFFF0195UL)
+#define VI_ATTR_TCPIP_HOSTNAME (0xBFFF0196UL)
+#define VI_ATTR_TCPIP_PORT (0x3FFF0197UL)
+#define VI_ATTR_TCPIP_DEVICE_NAME (0xBFFF0199UL)
+#define VI_ATTR_TCPIP_NODELAY (0x3FFF019AUL)
+#define VI_ATTR_TCPIP_KEEPALIVE (0x3FFF019BUL)
+#define VI_ATTR_4882_COMPLIANT (0x3FFF019FUL)
+#define VI_ATTR_USB_SERIAL_NUM (0xBFFF01A0UL)
+#define VI_ATTR_USB_INTFC_NUM (0x3FFF01A1UL)
+#define VI_ATTR_USB_PROTOCOL (0x3FFF01A7UL)
+#define VI_ATTR_USB_MAX_INTR_SIZE (0x3FFF01AFUL)
+#define VI_ATTR_PXI_DEV_NUM (0x3FFF0201UL)
+#define VI_ATTR_PXI_FUNC_NUM (0x3FFF0202UL)
+#define VI_ATTR_PXI_BUS_NUM (0x3FFF0205UL)
+#define VI_ATTR_PXI_CHASSIS (0x3FFF0206UL)
+#define VI_ATTR_PXI_SLOTPATH (0xBFFF0207UL)
+#define VI_ATTR_PXI_SLOT_LBUS_LEFT (0x3FFF0208UL)
+#define VI_ATTR_PXI_SLOT_LBUS_RIGHT (0x3FFF0209UL)
+#define VI_ATTR_PXI_TRIG_BUS (0x3FFF020AUL)
+#define VI_ATTR_PXI_STAR_TRIG_BUS (0x3FFF020BUL)
+#define VI_ATTR_PXI_STAR_TRIG_LINE (0x3FFF020CUL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR0 (0x3FFF0211UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR1 (0x3FFF0212UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR2 (0x3FFF0213UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR3 (0x3FFF0214UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR4 (0x3FFF0215UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR5 (0x3FFF0216UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR0 (0x3FFF0221UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR1 (0x3FFF0222UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR2 (0x3FFF0223UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR3 (0x3FFF0224UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR4 (0x3FFF0225UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR5 (0x3FFF0226UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR0 (0x3FFF0231UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR1 (0x3FFF0232UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR2 (0x3FFF0233UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR3 (0x3FFF0234UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR4 (0x3FFF0235UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR5 (0x3FFF0236UL)
+#define VI_ATTR_PXI_IS_EXPRESS (0x3FFF0240UL)
+#define VI_ATTR_PXI_SLOT_LWIDTH (0x3FFF0241UL)
+#define VI_ATTR_PXI_MAX_LWIDTH (0x3FFF0242UL)
+#define VI_ATTR_PXI_ACTUAL_LWIDTH (0x3FFF0243UL)
+#define VI_ATTR_PXI_DSTAR_BUS (0x3FFF0244UL)
+#define VI_ATTR_PXI_DSTAR_SET (0x3FFF0245UL)
+
+#define VI_ATTR_JOB_ID (0x3FFF4006UL)
+#define VI_ATTR_EVENT_TYPE (0x3FFF4010UL)
+#define VI_ATTR_SIGP_STATUS_ID (0x3FFF4011UL)
+#define VI_ATTR_RECV_TRIG_ID (0x3FFF4012UL)
+#define VI_ATTR_INTR_STATUS_ID (0x3FFF4023UL)
+#define VI_ATTR_STATUS (0x3FFF4025UL)
+#define VI_ATTR_RET_COUNT_32 (0x3FFF4026UL)
+#define VI_ATTR_BUFFER (0x3FFF4027UL)
+#define VI_ATTR_RECV_INTR_LEVEL (0x3FFF4041UL)
+#define VI_ATTR_OPER_NAME (0xBFFF4042UL)
+#define VI_ATTR_GPIB_RECV_CIC_STATE (0x3FFF4193UL)
+#define VI_ATTR_RECV_TCPIP_ADDR (0xBFFF4198UL)
+#define VI_ATTR_USB_RECV_INTR_SIZE (0x3FFF41B0UL)
+#define VI_ATTR_USB_RECV_INTR_DATA (0xBFFF41B1UL)
+
+/*- Attributes (platform dependent size) ------------------------------------*/
+
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+#define VI_ATTR_USER_DATA_64 (0x3FFF000AUL)
+#define VI_ATTR_RET_COUNT_64 (0x3FFF4028UL)
+#define VI_ATTR_USER_DATA (VI_ATTR_USER_DATA_64)
+#define VI_ATTR_RET_COUNT (VI_ATTR_RET_COUNT_64)
+#else
+#define VI_ATTR_USER_DATA (VI_ATTR_USER_DATA_32)
+#define VI_ATTR_RET_COUNT (VI_ATTR_RET_COUNT_32)
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+#define VI_ATTR_WIN_BASE_ADDR_64 (0x3FFF009BUL)
+#define VI_ATTR_WIN_SIZE_64 (0x3FFF009CUL)
+#define VI_ATTR_MEM_BASE_64 (0x3FFF00D0UL)
+#define VI_ATTR_MEM_SIZE_64 (0x3FFF00D1UL)
+#endif
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+#define VI_ATTR_WIN_BASE_ADDR (VI_ATTR_WIN_BASE_ADDR_64)
+#define VI_ATTR_WIN_SIZE (VI_ATTR_WIN_SIZE_64)
+#define VI_ATTR_MEM_BASE (VI_ATTR_MEM_BASE_64)
+#define VI_ATTR_MEM_SIZE (VI_ATTR_MEM_SIZE_64)
+#else
+#define VI_ATTR_WIN_BASE_ADDR (VI_ATTR_WIN_BASE_ADDR_32)
+#define VI_ATTR_WIN_SIZE (VI_ATTR_WIN_SIZE_32)
+#define VI_ATTR_MEM_BASE (VI_ATTR_MEM_BASE_32)
+#define VI_ATTR_MEM_SIZE (VI_ATTR_MEM_SIZE_32)
+#endif
+
+/*- Event Types -------------------------------------------------------------*/
+
+#define VI_EVENT_IO_COMPLETION (0x3FFF2009UL)
+#define VI_EVENT_TRIG (0xBFFF200AUL)
+#define VI_EVENT_SERVICE_REQ (0x3FFF200BUL)
+#define VI_EVENT_CLEAR (0x3FFF200DUL)
+#define VI_EVENT_EXCEPTION (0xBFFF200EUL)
+#define VI_EVENT_GPIB_CIC (0x3FFF2012UL)
+#define VI_EVENT_GPIB_TALK (0x3FFF2013UL)
+#define VI_EVENT_GPIB_LISTEN (0x3FFF2014UL)
+#define VI_EVENT_VXI_VME_SYSFAIL (0x3FFF201DUL)
+#define VI_EVENT_VXI_VME_SYSRESET (0x3FFF201EUL)
+#define VI_EVENT_VXI_SIGP (0x3FFF2020UL)
+#define VI_EVENT_VXI_VME_INTR (0xBFFF2021UL)
+#define VI_EVENT_PXI_INTR (0x3FFF2022UL)
+#define VI_EVENT_TCPIP_CONNECT (0x3FFF2036UL)
+#define VI_EVENT_USB_INTR (0x3FFF2037UL)
+
+#define VI_ALL_ENABLED_EVENTS (0x3FFF7FFFUL)
+
+/*- Completion and Error Codes ----------------------------------------------*/
+
+#define VI_SUCCESS_EVENT_EN (0x3FFF0002L) /* 3FFF0002, 1073676290 */
+#define VI_SUCCESS_EVENT_DIS (0x3FFF0003L) /* 3FFF0003, 1073676291 */
+#define VI_SUCCESS_QUEUE_EMPTY (0x3FFF0004L) /* 3FFF0004, 1073676292 */
+#define VI_SUCCESS_TERM_CHAR (0x3FFF0005L) /* 3FFF0005, 1073676293 */
+#define VI_SUCCESS_MAX_CNT (0x3FFF0006L) /* 3FFF0006, 1073676294 */
+#define VI_SUCCESS_DEV_NPRESENT (0x3FFF007DL) /* 3FFF007D, 1073676413 */
+#define VI_SUCCESS_TRIG_MAPPED (0x3FFF007EL) /* 3FFF007E, 1073676414 */
+#define VI_SUCCESS_QUEUE_NEMPTY (0x3FFF0080L) /* 3FFF0080, 1073676416 */
+#define VI_SUCCESS_NCHAIN (0x3FFF0098L) /* 3FFF0098, 1073676440 */
+#define VI_SUCCESS_NESTED_SHARED (0x3FFF0099L) /* 3FFF0099, 1073676441 */
+#define VI_SUCCESS_NESTED_EXCLUSIVE (0x3FFF009AL) /* 3FFF009A, 1073676442 */
+#define VI_SUCCESS_SYNC (0x3FFF009BL) /* 3FFF009B, 1073676443 */
+
+#define VI_WARN_QUEUE_OVERFLOW (0x3FFF000CL) /* 3FFF000C, 1073676300 */
+#define VI_WARN_CONFIG_NLOADED (0x3FFF0077L) /* 3FFF0077, 1073676407 */
+#define VI_WARN_NULL_OBJECT (0x3FFF0082L) /* 3FFF0082, 1073676418 */
+#define VI_WARN_NSUP_ATTR_STATE (0x3FFF0084L) /* 3FFF0084, 1073676420 */
+#define VI_WARN_UNKNOWN_STATUS (0x3FFF0085L) /* 3FFF0085, 1073676421 */
+#define VI_WARN_NSUP_BUF (0x3FFF0088L) /* 3FFF0088, 1073676424 */
+#define VI_WARN_EXT_FUNC_NIMPL (0x3FFF00A9L) /* 3FFF00A9, 1073676457 */
+
+#define VI_ERROR_SYSTEM_ERROR (_VI_ERROR+0x3FFF0000L) /* BFFF0000, -1073807360 */
+#define VI_ERROR_INV_OBJECT (_VI_ERROR+0x3FFF000EL) /* BFFF000E, -1073807346 */
+#define VI_ERROR_RSRC_LOCKED (_VI_ERROR+0x3FFF000FL) /* BFFF000F, -1073807345 */
+#define VI_ERROR_INV_EXPR (_VI_ERROR+0x3FFF0010L) /* BFFF0010, -1073807344 */
+#define VI_ERROR_RSRC_NFOUND (_VI_ERROR+0x3FFF0011L) /* BFFF0011, -1073807343 */
+#define VI_ERROR_INV_RSRC_NAME (_VI_ERROR+0x3FFF0012L) /* BFFF0012, -1073807342 */
+#define VI_ERROR_INV_ACC_MODE (_VI_ERROR+0x3FFF0013L) /* BFFF0013, -1073807341 */
+#define VI_ERROR_TMO (_VI_ERROR+0x3FFF0015L) /* BFFF0015, -1073807339 */
+#define VI_ERROR_CLOSING_FAILED (_VI_ERROR+0x3FFF0016L) /* BFFF0016, -1073807338 */
+#define VI_ERROR_INV_DEGREE (_VI_ERROR+0x3FFF001BL) /* BFFF001B, -1073807333 */
+#define VI_ERROR_INV_JOB_ID (_VI_ERROR+0x3FFF001CL) /* BFFF001C, -1073807332 */
+#define VI_ERROR_NSUP_ATTR (_VI_ERROR+0x3FFF001DL) /* BFFF001D, -1073807331 */
+#define VI_ERROR_NSUP_ATTR_STATE (_VI_ERROR+0x3FFF001EL) /* BFFF001E, -1073807330 */
+#define VI_ERROR_ATTR_READONLY (_VI_ERROR+0x3FFF001FL) /* BFFF001F, -1073807329 */
+#define VI_ERROR_INV_LOCK_TYPE (_VI_ERROR+0x3FFF0020L) /* BFFF0020, -1073807328 */
+#define VI_ERROR_INV_ACCESS_KEY (_VI_ERROR+0x3FFF0021L) /* BFFF0021, -1073807327 */
+#define VI_ERROR_INV_EVENT (_VI_ERROR+0x3FFF0026L) /* BFFF0026, -1073807322 */
+#define VI_ERROR_INV_MECH (_VI_ERROR+0x3FFF0027L) /* BFFF0027, -1073807321 */
+#define VI_ERROR_HNDLR_NINSTALLED (_VI_ERROR+0x3FFF0028L) /* BFFF0028, -1073807320 */
+#define VI_ERROR_INV_HNDLR_REF (_VI_ERROR+0x3FFF0029L) /* BFFF0029, -1073807319 */
+#define VI_ERROR_INV_CONTEXT (_VI_ERROR+0x3FFF002AL) /* BFFF002A, -1073807318 */
+#define VI_ERROR_QUEUE_OVERFLOW (_VI_ERROR+0x3FFF002DL) /* BFFF002D, -1073807315 */
+#define VI_ERROR_NENABLED (_VI_ERROR+0x3FFF002FL) /* BFFF002F, -1073807313 */
+#define VI_ERROR_ABORT (_VI_ERROR+0x3FFF0030L) /* BFFF0030, -1073807312 */
+#define VI_ERROR_RAW_WR_PROT_VIOL (_VI_ERROR+0x3FFF0034L) /* BFFF0034, -1073807308 */
+#define VI_ERROR_RAW_RD_PROT_VIOL (_VI_ERROR+0x3FFF0035L) /* BFFF0035, -1073807307 */
+#define VI_ERROR_OUTP_PROT_VIOL (_VI_ERROR+0x3FFF0036L) /* BFFF0036, -1073807306 */
+#define VI_ERROR_INP_PROT_VIOL (_VI_ERROR+0x3FFF0037L) /* BFFF0037, -1073807305 */
+#define VI_ERROR_BERR (_VI_ERROR+0x3FFF0038L) /* BFFF0038, -1073807304 */
+#define VI_ERROR_IN_PROGRESS (_VI_ERROR+0x3FFF0039L) /* BFFF0039, -1073807303 */
+#define VI_ERROR_INV_SETUP (_VI_ERROR+0x3FFF003AL) /* BFFF003A, -1073807302 */
+#define VI_ERROR_QUEUE_ERROR (_VI_ERROR+0x3FFF003BL) /* BFFF003B, -1073807301 */
+#define VI_ERROR_ALLOC (_VI_ERROR+0x3FFF003CL) /* BFFF003C, -1073807300 */
+#define VI_ERROR_INV_MASK (_VI_ERROR+0x3FFF003DL) /* BFFF003D, -1073807299 */
+#define VI_ERROR_IO (_VI_ERROR+0x3FFF003EL) /* BFFF003E, -1073807298 */
+#define VI_ERROR_INV_FMT (_VI_ERROR+0x3FFF003FL) /* BFFF003F, -1073807297 */
+#define VI_ERROR_NSUP_FMT (_VI_ERROR+0x3FFF0041L) /* BFFF0041, -1073807295 */
+#define VI_ERROR_LINE_IN_USE (_VI_ERROR+0x3FFF0042L) /* BFFF0042, -1073807294 */
+#define VI_ERROR_NSUP_MODE (_VI_ERROR+0x3FFF0046L) /* BFFF0046, -1073807290 */
+#define VI_ERROR_SRQ_NOCCURRED (_VI_ERROR+0x3FFF004AL) /* BFFF004A, -1073807286 */
+#define VI_ERROR_INV_SPACE (_VI_ERROR+0x3FFF004EL) /* BFFF004E, -1073807282 */
+#define VI_ERROR_INV_OFFSET (_VI_ERROR+0x3FFF0051L) /* BFFF0051, -1073807279 */
+#define VI_ERROR_INV_WIDTH (_VI_ERROR+0x3FFF0052L) /* BFFF0052, -1073807278 */
+#define VI_ERROR_NSUP_OFFSET (_VI_ERROR+0x3FFF0054L) /* BFFF0054, -1073807276 */
+#define VI_ERROR_NSUP_VAR_WIDTH (_VI_ERROR+0x3FFF0055L) /* BFFF0055, -1073807275 */
+#define VI_ERROR_WINDOW_NMAPPED (_VI_ERROR+0x3FFF0057L) /* BFFF0057, -1073807273 */
+#define VI_ERROR_RESP_PENDING (_VI_ERROR+0x3FFF0059L) /* BFFF0059, -1073807271 */
+#define VI_ERROR_NLISTENERS (_VI_ERROR+0x3FFF005FL) /* BFFF005F, -1073807265 */
+#define VI_ERROR_NCIC (_VI_ERROR+0x3FFF0060L) /* BFFF0060, -1073807264 */
+#define VI_ERROR_NSYS_CNTLR (_VI_ERROR+0x3FFF0061L) /* BFFF0061, -1073807263 */
+#define VI_ERROR_NSUP_OPER (_VI_ERROR+0x3FFF0067L) /* BFFF0067, -1073807257 */
+#define VI_ERROR_INTR_PENDING (_VI_ERROR+0x3FFF0068L) /* BFFF0068, -1073807256 */
+#define VI_ERROR_ASRL_PARITY (_VI_ERROR+0x3FFF006AL) /* BFFF006A, -1073807254 */
+#define VI_ERROR_ASRL_FRAMING (_VI_ERROR+0x3FFF006BL) /* BFFF006B, -1073807253 */
+#define VI_ERROR_ASRL_OVERRUN (_VI_ERROR+0x3FFF006CL) /* BFFF006C, -1073807252 */
+#define VI_ERROR_TRIG_NMAPPED (_VI_ERROR+0x3FFF006EL) /* BFFF006E, -1073807250 */
+#define VI_ERROR_NSUP_ALIGN_OFFSET (_VI_ERROR+0x3FFF0070L) /* BFFF0070, -1073807248 */
+#define VI_ERROR_USER_BUF (_VI_ERROR+0x3FFF0071L) /* BFFF0071, -1073807247 */
+#define VI_ERROR_RSRC_BUSY (_VI_ERROR+0x3FFF0072L) /* BFFF0072, -1073807246 */
+#define VI_ERROR_NSUP_WIDTH (_VI_ERROR+0x3FFF0076L) /* BFFF0076, -1073807242 */
+#define VI_ERROR_INV_PARAMETER (_VI_ERROR+0x3FFF0078L) /* BFFF0078, -1073807240 */
+#define VI_ERROR_INV_PROT (_VI_ERROR+0x3FFF0079L) /* BFFF0079, -1073807239 */
+#define VI_ERROR_INV_SIZE (_VI_ERROR+0x3FFF007BL) /* BFFF007B, -1073807237 */
+#define VI_ERROR_WINDOW_MAPPED (_VI_ERROR+0x3FFF0080L) /* BFFF0080, -1073807232 */
+#define VI_ERROR_NIMPL_OPER (_VI_ERROR+0x3FFF0081L) /* BFFF0081, -1073807231 */
+#define VI_ERROR_INV_LENGTH (_VI_ERROR+0x3FFF0083L) /* BFFF0083, -1073807229 */
+#define VI_ERROR_INV_MODE (_VI_ERROR+0x3FFF0091L) /* BFFF0091, -1073807215 */
+#define VI_ERROR_SESN_NLOCKED (_VI_ERROR+0x3FFF009CL) /* BFFF009C, -1073807204 */
+#define VI_ERROR_MEM_NSHARED (_VI_ERROR+0x3FFF009DL) /* BFFF009D, -1073807203 */
+#define VI_ERROR_LIBRARY_NFOUND (_VI_ERROR+0x3FFF009EL) /* BFFF009E, -1073807202 */
+#define VI_ERROR_NSUP_INTR (_VI_ERROR+0x3FFF009FL) /* BFFF009F, -1073807201 */
+#define VI_ERROR_INV_LINE (_VI_ERROR+0x3FFF00A0L) /* BFFF00A0, -1073807200 */
+#define VI_ERROR_FILE_ACCESS (_VI_ERROR+0x3FFF00A1L) /* BFFF00A1, -1073807199 */
+#define VI_ERROR_FILE_IO (_VI_ERROR+0x3FFF00A2L) /* BFFF00A2, -1073807198 */
+#define VI_ERROR_NSUP_LINE (_VI_ERROR+0x3FFF00A3L) /* BFFF00A3, -1073807197 */
+#define VI_ERROR_NSUP_MECH (_VI_ERROR+0x3FFF00A4L) /* BFFF00A4, -1073807196 */
+#define VI_ERROR_INTF_NUM_NCONFIG (_VI_ERROR+0x3FFF00A5L) /* BFFF00A5, -1073807195 */
+#define VI_ERROR_CONN_LOST (_VI_ERROR+0x3FFF00A6L) /* BFFF00A6, -1073807194 */
+#define VI_ERROR_MACHINE_NAVAIL (_VI_ERROR+0x3FFF00A7L) /* BFFF00A7, -1073807193 */
+#define VI_ERROR_NPERMISSION (_VI_ERROR+0x3FFF00A8L) /* BFFF00A8, -1073807192 */
+
+/*- Other VISA Definitions --------------------------------------------------*/
+
+#define VI_VERSION_MAJOR(ver) ((((ViVersion)ver) & 0xFFF00000UL) >> 20)
+#define VI_VERSION_MINOR(ver) ((((ViVersion)ver) & 0x000FFF00UL) >> 8)
+#define VI_VERSION_SUBMINOR(ver) ((((ViVersion)ver) & 0x000000FFUL) )
+
+#define VI_FIND_BUFLEN (256)
+
+#define VI_INTF_GPIB (1)
+#define VI_INTF_VXI (2)
+#define VI_INTF_GPIB_VXI (3)
+#define VI_INTF_ASRL (4)
+#define VI_INTF_PXI (5)
+#define VI_INTF_TCPIP (6)
+#define VI_INTF_USB (7)
+
+#define VI_PROT_NORMAL (1)
+#define VI_PROT_FDC (2)
+#define VI_PROT_HS488 (3)
+#define VI_PROT_4882_STRS (4)
+#define VI_PROT_USBTMC_VENDOR (5)
+
+#define VI_FDC_NORMAL (1)
+#define VI_FDC_STREAM (2)
+
+#define VI_LOCAL_SPACE (0)
+#define VI_A16_SPACE (1)
+#define VI_A24_SPACE (2)
+#define VI_A32_SPACE (3)
+#define VI_A64_SPACE (4)
+#define VI_PXI_ALLOC_SPACE (9)
+#define VI_PXI_CFG_SPACE (10)
+#define VI_PXI_BAR0_SPACE (11)
+#define VI_PXI_BAR1_SPACE (12)
+#define VI_PXI_BAR2_SPACE (13)
+#define VI_PXI_BAR3_SPACE (14)
+#define VI_PXI_BAR4_SPACE (15)
+#define VI_PXI_BAR5_SPACE (16)
+#define VI_OPAQUE_SPACE (0xFFFF)
+
+#define VI_UNKNOWN_LA (-1)
+#define VI_UNKNOWN_SLOT (-1)
+#define VI_UNKNOWN_LEVEL (-1)
+#define VI_UNKNOWN_CHASSIS (-1)
+
+#define VI_QUEUE (1)
+#define VI_HNDLR (2)
+#define VI_SUSPEND_HNDLR (4)
+#define VI_ALL_MECH (0xFFFF)
+
+#define VI_ANY_HNDLR (0)
+
+#define VI_TRIG_ALL (-2)
+#define VI_TRIG_SW (-1)
+#define VI_TRIG_TTL0 (0)
+#define VI_TRIG_TTL1 (1)
+#define VI_TRIG_TTL2 (2)
+#define VI_TRIG_TTL3 (3)
+#define VI_TRIG_TTL4 (4)
+#define VI_TRIG_TTL5 (5)
+#define VI_TRIG_TTL6 (6)
+#define VI_TRIG_TTL7 (7)
+#define VI_TRIG_ECL0 (8)
+#define VI_TRIG_ECL1 (9)
+#define VI_TRIG_PANEL_IN (27)
+#define VI_TRIG_PANEL_OUT (28)
+
+#define VI_TRIG_PROT_DEFAULT (0)
+#define VI_TRIG_PROT_ON (1)
+#define VI_TRIG_PROT_OFF (2)
+#define VI_TRIG_PROT_SYNC (5)
+#define VI_TRIG_PROT_RESERVE (6)
+#define VI_TRIG_PROT_UNRESERVE (7)
+
+#define VI_READ_BUF (1)
+#define VI_WRITE_BUF (2)
+#define VI_READ_BUF_DISCARD (4)
+#define VI_WRITE_BUF_DISCARD (8)
+#define VI_IO_IN_BUF (16)
+#define VI_IO_OUT_BUF (32)
+#define VI_IO_IN_BUF_DISCARD (64)
+#define VI_IO_OUT_BUF_DISCARD (128)
+
+#define VI_FLUSH_ON_ACCESS (1)
+#define VI_FLUSH_WHEN_FULL (2)
+#define VI_FLUSH_DISABLE (3)
+
+#define VI_NMAPPED (1)
+#define VI_USE_OPERS (2)
+#define VI_DEREF_ADDR (3)
+#define VI_DEREF_ADDR_BYTE_SWAP (4)
+
+#define VI_TMO_IMMEDIATE (0L)
+#define VI_TMO_INFINITE (0xFFFFFFFFUL)
+
+#define VI_NO_LOCK (0)
+#define VI_EXCLUSIVE_LOCK (1)
+#define VI_SHARED_LOCK (2)
+#define VI_LOAD_CONFIG (4)
+
+#define VI_NO_SEC_ADDR (0xFFFF)
+
+#define VI_ASRL_PAR_NONE (0)
+#define VI_ASRL_PAR_ODD (1)
+#define VI_ASRL_PAR_EVEN (2)
+#define VI_ASRL_PAR_MARK (3)
+#define VI_ASRL_PAR_SPACE (4)
+
+#define VI_ASRL_STOP_ONE (10)
+#define VI_ASRL_STOP_ONE5 (15)
+#define VI_ASRL_STOP_TWO (20)
+
+#define VI_ASRL_FLOW_NONE (0)
+#define VI_ASRL_FLOW_XON_XOFF (1)
+#define VI_ASRL_FLOW_RTS_CTS (2)
+#define VI_ASRL_FLOW_DTR_DSR (4)
+
+#define VI_ASRL_END_NONE (0)
+#define VI_ASRL_END_LAST_BIT (1)
+#define VI_ASRL_END_TERMCHAR (2)
+#define VI_ASRL_END_BREAK (3)
+
+#define VI_STATE_ASSERTED (1)
+#define VI_STATE_UNASSERTED (0)
+#define VI_STATE_UNKNOWN (-1)
+
+#define VI_BIG_ENDIAN (0)
+#define VI_LITTLE_ENDIAN (1)
+
+#define VI_DATA_PRIV (0)
+#define VI_DATA_NPRIV (1)
+#define VI_PROG_PRIV (2)
+#define VI_PROG_NPRIV (3)
+#define VI_BLCK_PRIV (4)
+#define VI_BLCK_NPRIV (5)
+#define VI_D64_PRIV (6)
+#define VI_D64_NPRIV (7)
+
+#define VI_WIDTH_8 (1)
+#define VI_WIDTH_16 (2)
+#define VI_WIDTH_32 (4)
+#define VI_WIDTH_64 (8)
+
+#define VI_GPIB_REN_DEASSERT (0)
+#define VI_GPIB_REN_ASSERT (1)
+#define VI_GPIB_REN_DEASSERT_GTL (2)
+#define VI_GPIB_REN_ASSERT_ADDRESS (3)
+#define VI_GPIB_REN_ASSERT_LLO (4)
+#define VI_GPIB_REN_ASSERT_ADDRESS_LLO (5)
+#define VI_GPIB_REN_ADDRESS_GTL (6)
+
+#define VI_GPIB_ATN_DEASSERT (0)
+#define VI_GPIB_ATN_ASSERT (1)
+#define VI_GPIB_ATN_DEASSERT_HANDSHAKE (2)
+#define VI_GPIB_ATN_ASSERT_IMMEDIATE (3)
+
+#define VI_GPIB_HS488_DISABLED (0)
+#define VI_GPIB_HS488_NIMPL (-1)
+
+#define VI_GPIB_UNADDRESSED (0)
+#define VI_GPIB_TALKER (1)
+#define VI_GPIB_LISTENER (2)
+
+#define VI_VXI_CMD16 (0x0200)
+#define VI_VXI_CMD16_RESP16 (0x0202)
+#define VI_VXI_RESP16 (0x0002)
+#define VI_VXI_CMD32 (0x0400)
+#define VI_VXI_CMD32_RESP16 (0x0402)
+#define VI_VXI_CMD32_RESP32 (0x0404)
+#define VI_VXI_RESP32 (0x0004)
+
+#define VI_ASSERT_SIGNAL (-1)
+#define VI_ASSERT_USE_ASSIGNED (0)
+#define VI_ASSERT_IRQ1 (1)
+#define VI_ASSERT_IRQ2 (2)
+#define VI_ASSERT_IRQ3 (3)
+#define VI_ASSERT_IRQ4 (4)
+#define VI_ASSERT_IRQ5 (5)
+#define VI_ASSERT_IRQ6 (6)
+#define VI_ASSERT_IRQ7 (7)
+
+#define VI_UTIL_ASSERT_SYSRESET (1)
+#define VI_UTIL_ASSERT_SYSFAIL (2)
+#define VI_UTIL_DEASSERT_SYSFAIL (3)
+
+#define VI_VXI_CLASS_MEMORY (0)
+#define VI_VXI_CLASS_EXTENDED (1)
+#define VI_VXI_CLASS_MESSAGE (2)
+#define VI_VXI_CLASS_REGISTER (3)
+#define VI_VXI_CLASS_OTHER (4)
+
+#define VI_PXI_ADDR_NONE (0)
+#define VI_PXI_ADDR_MEM (1)
+#define VI_PXI_ADDR_IO (2)
+#define VI_PXI_ADDR_CFG (3)
+
+#define VI_TRIG_UNKNOWN (-1)
+
+#define VI_PXI_LBUS_UNKNOWN (-1)
+#define VI_PXI_LBUS_NONE (0)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_0 (1000)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_1 (1001)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_2 (1002)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_3 (1003)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_4 (1004)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_5 (1005)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_6 (1006)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_7 (1007)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_8 (1008)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_9 (1009)
+#define VI_PXI_STAR_TRIG_CONTROLLER (1413)
+
+/*- Backward Compatibility Macros -------------------------------------------*/
+
+#define viGetDefaultRM(vi) viOpenDefaultRM(vi)
+#define VI_ERROR_INV_SESSION (VI_ERROR_INV_OBJECT)
+#define VI_INFINITE (VI_TMO_INFINITE)
+#define VI_NORMAL (VI_PROT_NORMAL)
+#define VI_FDC (VI_PROT_FDC)
+#define VI_HS488 (VI_PROT_HS488)
+#define VI_ASRL488 (VI_PROT_4882_STRS)
+#define VI_ASRL_IN_BUF (VI_IO_IN_BUF)
+#define VI_ASRL_OUT_BUF (VI_IO_OUT_BUF)
+#define VI_ASRL_IN_BUF_DISCARD (VI_IO_IN_BUF_DISCARD)
+#define VI_ASRL_OUT_BUF_DISCARD (VI_IO_OUT_BUF_DISCARD)
+
+/*- National Instruments ----------------------------------------------------*/
+
+#define VI_INTF_RIO (8)
+#define VI_INTF_FIREWIRE (9)
+
+#define VI_ATTR_SYNC_MXI_ALLOW_EN (0x3FFF0161UL) /* ViBoolean, read/write */
+
+/* This is for VXI SERVANT resources */
+
+#define VI_EVENT_VXI_DEV_CMD (0xBFFF200FUL)
+#define VI_ATTR_VXI_DEV_CMD_TYPE (0x3FFF4037UL) /* ViInt16, read-only */
+#define VI_ATTR_VXI_DEV_CMD_VALUE (0x3FFF4038UL) /* ViUInt32, read-only */
+
+#define VI_VXI_DEV_CMD_TYPE_16 (16)
+#define VI_VXI_DEV_CMD_TYPE_32 (32)
+
+ViStatus _VI_FUNC viVxiServantResponse(ViSession vi, ViInt16 mode, ViUInt32 resp);
+/* mode values include VI_VXI_RESP16, VI_VXI_RESP32, and the next 2 values */
+#define VI_VXI_RESP_NONE (0)
+#define VI_VXI_RESP_PROT_ERROR (-1)
+
+/* This allows extended Serial support on Win32 and on NI ENET Serial products */
+
+#define VI_ATTR_ASRL_DISCARD_NULL (0x3FFF00B0UL)
+#define VI_ATTR_ASRL_CONNECTED (0x3FFF01BBUL)
+#define VI_ATTR_ASRL_BREAK_STATE (0x3FFF01BCUL)
+#define VI_ATTR_ASRL_BREAK_LEN (0x3FFF01BDUL)
+#define VI_ATTR_ASRL_ALLOW_TRANSMIT (0x3FFF01BEUL)
+#define VI_ATTR_ASRL_WIRE_MODE (0x3FFF01BFUL)
+
+#define VI_ASRL_WIRE_485_4 (0)
+#define VI_ASRL_WIRE_485_2_DTR_ECHO (1)
+#define VI_ASRL_WIRE_485_2_DTR_CTRL (2)
+#define VI_ASRL_WIRE_485_2_AUTO (3)
+#define VI_ASRL_WIRE_232_DTE (128)
+#define VI_ASRL_WIRE_232_DCE (129)
+#define VI_ASRL_WIRE_232_AUTO (130)
+
+#define VI_EVENT_ASRL_BREAK (0x3FFF2023UL)
+#define VI_EVENT_ASRL_CTS (0x3FFF2029UL)
+#define VI_EVENT_ASRL_DSR (0x3FFF202AUL)
+#define VI_EVENT_ASRL_DCD (0x3FFF202CUL)
+#define VI_EVENT_ASRL_RI (0x3FFF202EUL)
+#define VI_EVENT_ASRL_CHAR (0x3FFF2035UL)
+#define VI_EVENT_ASRL_TERMCHAR (0x3FFF2024UL)
+
+/* This is for fast viPeek/viPoke macros */
+
+#if defined(NIVISA_PEEKPOKE)
+
+#if defined(NIVISA_PEEKPOKE_SUPP)
+#undef NIVISA_PEEKPOKE_SUPP
+#endif
+
+#if (defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_)
+/* This macro is supported for all Win32 compilers, including CVI. */
+#define NIVISA_PEEKPOKE_SUPP
+#elif (defined(_WINDOWS) || defined(_Windows)) && !defined(_CVI_) && !defined(_NI_mswin16_)
+/* This macro is supported for Borland and Microsoft compilers on Win16, but not CVI. */
+#define NIVISA_PEEKPOKE_SUPP
+#elif defined(_CVI_) && defined(_NI_sparc_)
+/* This macro is supported for Solaris 1 and 2, from CVI only. */
+#define NIVISA_PEEKPOKE_SUPP
+#else
+/* This macro is not supported on other platforms. */
+#endif
+
+#if defined(NIVISA_PEEKPOKE_SUPP)
+
+extern ViBoolean NI_viImplVISA1;
+ViStatus _VI_FUNC NI_viOpenDefaultRM (ViPSession vi);
+#define viOpenDefaultRM(vi) NI_viOpenDefaultRM(vi)
+
+#define viPeek8(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((ViPUInt8)(val)) = *((volatile ViUInt8 _VI_PTR)(addr))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPeek8)((vi),(addr),(val)); \
+ } \
+ }
+
+#define viPoke8(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((volatile ViUInt8 _VI_PTR)(addr)) = ((ViUInt8)(val))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPoke8)((vi),(addr),(val)); \
+ } \
+ }
+
+#define viPeek16(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((ViPUInt16)(val)) = *((volatile ViUInt16 _VI_PTR)(addr))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPeek16)((vi),(addr),(val)); \
+ } \
+ }
+
+#define viPoke16(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((volatile ViUInt16 _VI_PTR)(addr)) = ((ViUInt16)(val))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPoke16)((vi),(addr),(val)); \
+ } \
+ }
+
+#define viPeek32(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((ViPUInt32)(val)) = *((volatile ViUInt32 _VI_PTR)(addr))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPeek32)((vi),(addr),(val)); \
+ } \
+ }
+
+#define viPoke32(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((volatile ViUInt32 _VI_PTR)(addr)) = ((ViUInt32)(val))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPoke32)((vi),(addr),(val)); \
+ } \
+ }
+
+#endif
+
+#endif
+
+#if defined(NIVISA_PXI) || defined(PXISAVISA_PXI)
+
+#if 0
+/* The following 2 attributes were incorrectly implemented in earlier
+ versions of NI-VISA. You should now query VI_ATTR_MANF_ID or
+ VI_ATTR_MODEL_CODE. Those attributes contain sub-vendor information
+ when it exists. To get both the actual primary and subvendor codes
+ from the device, you should call viIn16 using VI_PXI_CFG_SPACE. */
+#define VI_ATTR_PXI_SUB_MANF_ID (0x3FFF0203UL)
+#define VI_ATTR_PXI_SUB_MODEL_CODE (0x3FFF0204UL)
+#endif
+
+#define VI_ATTR_PXI_SRC_TRIG_BUS (0x3FFF020DUL)
+#define VI_ATTR_PXI_DEST_TRIG_BUS (0x3FFF020EUL)
+
+#define VI_ATTR_PXI_RECV_INTR_SEQ (0x3FFF4240UL)
+#define VI_ATTR_PXI_RECV_INTR_DATA (0x3FFF4241UL)
+
+#endif
+
+#if defined(NIVISA_USB)
+
+#define VI_ATTR_USB_BULK_OUT_PIPE (0x3FFF01A2UL)
+#define VI_ATTR_USB_BULK_IN_PIPE (0x3FFF01A3UL)
+#define VI_ATTR_USB_INTR_IN_PIPE (0x3FFF01A4UL)
+#define VI_ATTR_USB_CLASS (0x3FFF01A5UL)
+#define VI_ATTR_USB_SUBCLASS (0x3FFF01A6UL)
+#define VI_ATTR_USB_ALT_SETTING (0x3FFF01A8UL)
+#define VI_ATTR_USB_END_IN (0x3FFF01A9UL)
+#define VI_ATTR_USB_NUM_INTFCS (0x3FFF01AAUL)
+#define VI_ATTR_USB_NUM_PIPES (0x3FFF01ABUL)
+#define VI_ATTR_USB_BULK_OUT_STATUS (0x3FFF01ACUL)
+#define VI_ATTR_USB_BULK_IN_STATUS (0x3FFF01ADUL)
+#define VI_ATTR_USB_INTR_IN_STATUS (0x3FFF01AEUL)
+#define VI_ATTR_USB_CTRL_PIPE (0x3FFF01B0UL)
+
+#define VI_USB_PIPE_STATE_UNKNOWN (-1)
+#define VI_USB_PIPE_READY (0)
+#define VI_USB_PIPE_STALLED (1)
+
+#define VI_USB_END_NONE (0)
+#define VI_USB_END_SHORT (4)
+#define VI_USB_END_SHORT_OR_COUNT (5)
+
+#endif
+
+#define VI_ATTR_FIREWIRE_DEST_UPPER_OFFSET (0x3FFF01F0UL)
+#define VI_ATTR_FIREWIRE_SRC_UPPER_OFFSET (0x3FFF01F1UL)
+#define VI_ATTR_FIREWIRE_WIN_UPPER_OFFSET (0x3FFF01F2UL)
+#define VI_ATTR_FIREWIRE_VENDOR_ID (0x3FFF01F3UL)
+#define VI_ATTR_FIREWIRE_LOWER_CHIP_ID (0x3FFF01F4UL)
+#define VI_ATTR_FIREWIRE_UPPER_CHIP_ID (0x3FFF01F5UL)
+
+#define VI_FIREWIRE_DFLT_SPACE (5)
+
+#if defined(__cplusplus) || defined(__cplusplus__)
+ }
+#endif
+
+#endif
+
+/*- The End -----------------------------------------------------------------*/
diff --git a/aos/externals/WPILib/WPILib/visa/visatype.h b/aos/externals/WPILib/WPILib/visa/visatype.h
new file mode 100644
index 0000000..ef089dd
--- /dev/null
+++ b/aos/externals/WPILib/WPILib/visa/visatype.h
@@ -0,0 +1,201 @@
+/*---------------------------------------------------------------------------*/
+/* Distributed by IVI Foundation Inc. */
+/* */
+/* Do not modify the contents of this file. */
+/*---------------------------------------------------------------------------*/
+/* */
+/* Title : VISATYPE.H */
+/* Date : 04-14-2006 */
+/* Purpose : Fundamental VISA data types and macro definitions */
+/* */
+/*---------------------------------------------------------------------------*/
+
+#ifndef __VISATYPE_HEADER__
+#define __VISATYPE_HEADER__
+
+#if defined(_WIN64)
+#define _VI_FAR
+#define _VI_FUNC __fastcall
+#define _VI_FUNCC __fastcall
+#define _VI_FUNCH __fastcall
+#define _VI_SIGNED signed
+#elif (defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_)
+#define _VI_FAR
+#define _VI_FUNC __stdcall
+#define _VI_FUNCC __cdecl
+#define _VI_FUNCH __stdcall
+#define _VI_SIGNED signed
+#elif defined(_CVI_) && defined(_NI_i386_)
+#define _VI_FAR
+#define _VI_FUNC _pascal
+#define _VI_FUNCC
+#define _VI_FUNCH _pascal
+#define _VI_SIGNED signed
+#elif (defined(_WINDOWS) || defined(_Windows)) && !defined(_NI_mswin16_)
+#define _VI_FAR _far
+#define _VI_FUNC _far _pascal _export
+#define _VI_FUNCC _far _cdecl _export
+#define _VI_FUNCH _far _pascal
+#define _VI_SIGNED signed
+#elif (defined(hpux) || defined(__hpux)) && (defined(__cplusplus) || defined(__cplusplus__))
+#define _VI_FAR
+#define _VI_FUNC
+#define _VI_FUNCC
+#define _VI_FUNCH
+#define _VI_SIGNED
+#else
+#define _VI_FAR
+#define _VI_FUNC
+#define _VI_FUNCC
+#define _VI_FUNCH
+#define _VI_SIGNED signed
+#endif
+
+#define _VI_ERROR (-2147483647L-1) /* 0x80000000 */
+#define _VI_PTR _VI_FAR *
+
+/*- VISA Types --------------------------------------------------------------*/
+
+#ifndef _VI_INT64_UINT64_DEFINED
+#if defined(_WIN64) || ((defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_))
+#if (defined(_MSC_VER) && (_MSC_VER >= 1200)) || (defined(_CVI_) && (_CVI_ >= 700)) || (defined(__BORLANDC__) && (__BORLANDC__ >= 0x0520))
+typedef unsigned __int64 ViUInt64;
+typedef _VI_SIGNED __int64 ViInt64;
+#define _VI_INT64_UINT64_DEFINED
+#if defined(_WIN64)
+#define _VISA_ENV_IS_64_BIT
+#else
+/* This is a 32-bit OS, not a 64-bit OS */
+#endif
+#endif
+#elif defined(__GNUC__) && (__GNUC__ >= 3)
+#include <limits.h>
+#include <sys/types.h>
+typedef u_int64_t ViUInt64;
+typedef int64_t ViInt64;
+#define _VI_INT64_UINT64_DEFINED
+#if defined(LONG_MAX) && (LONG_MAX > 0x7FFFFFFFL)
+#define _VISA_ENV_IS_64_BIT
+#else
+/* This is a 32-bit OS, not a 64-bit OS */
+#endif
+#else
+/* This platform does not support 64-bit types */
+#endif
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+typedef ViUInt64 _VI_PTR ViPUInt64;
+typedef ViUInt64 _VI_PTR ViAUInt64;
+typedef ViInt64 _VI_PTR ViPInt64;
+typedef ViInt64 _VI_PTR ViAInt64;
+#endif
+
+#if defined(LONG_MAX) && (LONG_MAX > 0x7FFFFFFFL)
+typedef unsigned int ViUInt32;
+typedef _VI_SIGNED int ViInt32;
+#else
+typedef unsigned long ViUInt32;
+typedef _VI_SIGNED long ViInt32;
+#endif
+
+typedef ViUInt32 _VI_PTR ViPUInt32;
+typedef ViUInt32 _VI_PTR ViAUInt32;
+typedef ViInt32 _VI_PTR ViPInt32;
+typedef ViInt32 _VI_PTR ViAInt32;
+
+typedef unsigned short ViUInt16;
+typedef ViUInt16 _VI_PTR ViPUInt16;
+typedef ViUInt16 _VI_PTR ViAUInt16;
+
+typedef _VI_SIGNED short ViInt16;
+typedef ViInt16 _VI_PTR ViPInt16;
+typedef ViInt16 _VI_PTR ViAInt16;
+
+typedef unsigned char ViUInt8;
+typedef ViUInt8 _VI_PTR ViPUInt8;
+typedef ViUInt8 _VI_PTR ViAUInt8;
+
+typedef _VI_SIGNED char ViInt8;
+typedef ViInt8 _VI_PTR ViPInt8;
+typedef ViInt8 _VI_PTR ViAInt8;
+
+typedef char ViChar;
+typedef ViChar _VI_PTR ViPChar;
+typedef ViChar _VI_PTR ViAChar;
+
+typedef unsigned char ViByte;
+typedef ViByte _VI_PTR ViPByte;
+typedef ViByte _VI_PTR ViAByte;
+
+typedef void _VI_PTR ViAddr;
+typedef ViAddr _VI_PTR ViPAddr;
+typedef ViAddr _VI_PTR ViAAddr;
+
+typedef float ViReal32;
+typedef ViReal32 _VI_PTR ViPReal32;
+typedef ViReal32 _VI_PTR ViAReal32;
+
+typedef double ViReal64;
+typedef ViReal64 _VI_PTR ViPReal64;
+typedef ViReal64 _VI_PTR ViAReal64;
+
+typedef ViPByte ViBuf;
+typedef ViPByte ViPBuf;
+typedef ViPByte _VI_PTR ViABuf;
+
+typedef ViPChar ViString;
+typedef ViPChar ViPString;
+typedef ViPChar _VI_PTR ViAString;
+
+typedef ViString ViRsrc;
+typedef ViString ViPRsrc;
+typedef ViString _VI_PTR ViARsrc;
+
+typedef ViUInt16 ViBoolean;
+typedef ViBoolean _VI_PTR ViPBoolean;
+typedef ViBoolean _VI_PTR ViABoolean;
+
+typedef ViInt32 ViStatus;
+typedef ViStatus _VI_PTR ViPStatus;
+typedef ViStatus _VI_PTR ViAStatus;
+
+typedef ViUInt32 ViVersion;
+typedef ViVersion _VI_PTR ViPVersion;
+typedef ViVersion _VI_PTR ViAVersion;
+
+typedef ViUInt32 ViObject;
+typedef ViObject _VI_PTR ViPObject;
+typedef ViObject _VI_PTR ViAObject;
+
+typedef ViObject ViSession;
+typedef ViSession _VI_PTR ViPSession;
+typedef ViSession _VI_PTR ViASession;
+
+typedef ViUInt32 ViAttr;
+
+#ifndef _VI_CONST_STRING_DEFINED
+typedef const ViChar * ViConstString;
+#define _VI_CONST_STRING_DEFINED
+#endif
+
+/*- Completion and Error Codes ----------------------------------------------*/
+
+#define VI_SUCCESS (0L)
+
+/*- Other VISA Definitions --------------------------------------------------*/
+
+#define VI_NULL (0)
+
+#define VI_TRUE (1)
+#define VI_FALSE (0)
+
+/*- Backward Compatibility Macros -------------------------------------------*/
+
+#define VISAFN _VI_FUNC
+#define ViPtr _VI_PTR
+
+#endif
+
+/*- The End -----------------------------------------------------------------*/
+
diff --git a/aos/externals/WPILib/make.rb b/aos/externals/WPILib/make.rb
new file mode 100644
index 0000000..a22969d
--- /dev/null
+++ b/aos/externals/WPILib/make.rb
@@ -0,0 +1,23 @@
+
+$excludes = [/Vision2009/,/CInterfaces/,/NetworkTables/,/SmartDashboard/,/Commands/,/Buttons/,/Preferences/,/swp$/]
+
+files = `find WPILib`.split(/\n/).collect do |file|
+ if(file =~ /.*\.cpp/)
+ file.gsub!(/cpp\Z/,"o")
+ $excludes.each do |exclude|
+ if(file && file =~ exclude)
+ file = nil
+ end
+ end
+ file
+ end
+end.compact
+
+make = "make -f ../module.mk"
+defines = "DEFINES=-D\'SVN_REV=\\\"2262\\\"\'"
+added_includes = "ADDED_INCLUDES=-I./WPILib/"
+outfile = "wpilib.out PROJECT_TARGET=wpilib.out"
+objects = "PROJECT_OBJECTS=\"#{files.join(" ")}\""
+
+cmd = "#{make} #{outfile} #{added_includes} #{defines} #{objects}"
+system cmd
diff --git a/aos/externals/gtest.patch b/aos/externals/gtest.patch
new file mode 100644
index 0000000..6caba01
--- /dev/null
+++ b/aos/externals/gtest.patch
@@ -0,0 +1,63 @@
+diff -rupN gtest-1.6.0-p1/fused-src/gtest/gtest-all.cc gtest-1.6.0/fused-src/gtest/gtest-all.cc
+--- gtest-1.6.0-p1/fused-src/gtest/gtest-all.cc 2011-04-15 12:54:57.000000000 -0700
++++ gtest-1.6.0/fused-src/gtest/gtest-all.cc 2012-11-12 17:42:37.881573135 -0800
+@@ -379,7 +379,25 @@ class GTEST_API_ SingleFailureChecker {
+
+ // cpplint thinks that the header is already included, so we want to
+ // silence it.
++#ifdef __VXWORKS__
++# include <time.h> // NOLINT
++# include <sys/times.h> // NOLINT
++static inline int gettimeofday(struct timeval *tv, void *) {
++ struct timespec ts;
++
++ if (clock_gettime(CLOCK_REALTIME, &ts) != 0) {
++ printf("Gettimeofday error\n");
++ tv->tv_sec = 0;
++ tv->tv_usec = 0;
++ return -1;
++ }
++ tv->tv_sec = ts.tv_sec;
++ tv->tv_usec = ts.tv_nsec/1000;
++ return 0;
++}
++#else
+ # include <sys/time.h> // NOLINT
++#endif
+ # include <unistd.h> // NOLINT
+
+ #endif // GTEST_OS_LINUX
+@@ -7751,6 +7769,8 @@ bool FilePath::CreateFolder() const {
+ delete [] unicode;
+ #elif GTEST_OS_WINDOWS
+ int result = _mkdir(pathname_.c_str());
++#elif defined(__VXWORKS__)
++ int result = mkdir(pathname_.c_str());
+ #else
+ int result = mkdir(pathname_.c_str(), 0777);
+ #endif // GTEST_OS_WINDOWS_MOBILE
+@@ -7870,7 +7890,7 @@ void FilePath::Normalize() {
+ namespace testing {
+ namespace internal {
+
+-#if defined(_MSC_VER) || defined(__BORLANDC__)
++#if defined(_MSC_VER) || defined(__BORLANDC__) || defined(__VXWORKS__)
+ // MSVC and C++Builder do not provide a definition of STDERR_FILENO.
+ const int kStdOutFileno = 1;
+ const int kStdErrFileno = 2;
+diff -rupN gtest-1.6.0-p1/include/gtest/internal/gtest-port.h gtest-1.6.0/include/gtest/internal/gtest-port.h
+--- gtest-1.6.0-p1/include/gtest/internal/gtest-port.h 2011-04-15 12:49:10.000000000 -0700
++++ gtest-1.6.0/include/gtest/internal/gtest-port.h 2012-11-12 17:27:33.536801263 -0800
+@@ -197,6 +197,12 @@
+ #include <sstream> // NOLINT
+ #include <string> // NOLINT
+
++#ifdef __VXWORKS__
++int read(int fd, void *buf, size_t count);
++int write(int fd, const void *buf, size_t count);
++int close(int fd);
++#endif
++
+ #define GTEST_DEV_EMAIL_ "googletestframework@@googlegroups.com"
+ #define GTEST_FLAG_PREFIX_ "gtest_"
+ #define GTEST_FLAG_PREFIX_DASH_ "gtest-"
diff --git a/aos/externals/gyp.patch b/aos/externals/gyp.patch
new file mode 100644
index 0000000..9019406
--- /dev/null
+++ b/aos/externals/gyp.patch
@@ -0,0 +1,21 @@
+diff -rupN before/pylib/gyp/input.py after/pylib/gyp/input.py
+--- before/pylib/gyp/input.py 2012-11-20 16:38:09.394784918 -0800
++++ after/pylib/gyp/input.py 2012-11-20 16:39:10.527105964 -0800
+@@ -2156,17 +2156,6 @@ def ValidateSourcesInTarget(target, targ
+ basename = os.path.basename(name) # Don't include extension.
+ basenames.setdefault(basename, []).append(source)
+
+- error = ''
+- for basename, files in basenames.iteritems():
+- if len(files) > 1:
+- error += ' %s: %s\n' % (basename, ' '.join(files))
+-
+- if error:
+- print ('static library %s has several files with the same basename:\n' %
+- target + error + 'Some build systems, e.g. MSVC08, '
+- 'cannot handle that.')
+- raise KeyError, 'Duplicate basenames in sources section, see list above'
+-
+
+ def ValidateRulesInTarget(target, target_dict, extra_sources_for_rules):
+ """Ensures that the rules sections in target_dict are valid and consistent,
diff --git a/aos/externals/v4l-utils.patch b/aos/externals/v4l-utils.patch
new file mode 100644
index 0000000..3f296bf
--- /dev/null
+++ b/aos/externals/v4l-utils.patch
@@ -0,0 +1,22 @@
+--- utils/v4l2-ctl/Makefile 2012-07-22 14:29:00.182803000 -0700
++++ utils/v4l2-ctl/Makefile 2012-07-22 14:29:13.046885458 -0700
+@@ -13,7 +13,7 @@
+ $(CC) $(LDFLAGS) -o $@ $^ -lm
+
+ v4l2-ctl: v4l2-ctl.o
+- $(CXX) $(LDFLAGS) -o $@ $^ -lv4l2 -lv4lconvert -lrt
++ $(CXX) $(LDFLAGS) -o $@ $^ -lv4l2 -lv4lconvert -lrt -ljpeg
+
+ install: $(TARGETS)
+ mkdir -p $(DESTDIR)$(PREFIX)/bin
+--- utils/v4l2-compliance/Makefile 2012-07-22 14:28:01.850429221 -0700
++++ utils/v4l2-compliance/Makefile 2012-07-22 14:28:16.434522654 -0700
+@@ -6,7 +6,7 @@
+
+ v4l2-compliance: v4l2-compliance.o v4l2-test-debug.o v4l2-test-input-output.o \
+ v4l2-test-controls.o v4l2-test-io-config.o v4l2-test-formats.o
+- $(CXX) $(LDFLAGS) -o $@ $^ -lv4l2 -lv4lconvert -lrt
++ $(CXX) $(LDFLAGS) -o $@ $^ -lv4l2 -lv4lconvert -lrt -ljpeg
+
+ install: $(TARGETS)
+ mkdir -p $(DESTDIR)$(PREFIX)/bin
diff --git a/aos/map_utils.h b/aos/map_utils.h
new file mode 100644
index 0000000..5b85091
--- /dev/null
+++ b/aos/map_utils.h
@@ -0,0 +1,30 @@
+#ifndef AOS_MAP_UTILS_H_
+#define AOS_MAP_UTILS_H_
+
+// TODO(aschuh): Template std::map as well.
+// Maps the key to the value, inserting it if it isn't there, or replacing it if
+// it is. Returns true if the key was added and false if it was replaced.
+template <typename K, typename V>
+bool InsertIntoMap(std::map<K, V> *my_map, const K &key, const V &new_value) {
+ std::pair<typename std::map<K, V>::iterator, bool> element;
+ element = my_map->insert(std::pair<K,V>(key, new_value));
+ if (element.second == false) {
+ element.first->second = new_value;
+ }
+ return element.second;
+}
+
+// Gets the value for the key from the map.
+// Returns true if the key was found and then populates *value with the value.
+// Otherwise, leaves value alone and returns false.
+template <typename K, typename V>
+bool GetFromMap(const std::map<K, V> &my_map, const K &key, V *value) {
+ typename std::map<K, V>::const_iterator element = my_map.find(key);
+ if (element != my_map.end()) {
+ *value = element->second;
+ return true;
+ }
+ return false;
+}
+
+#endif // AOS_MAP_UTILS_H_
diff --git a/aos/vim/act.vim b/aos/vim/act.vim
new file mode 100644
index 0000000..b541ac2
--- /dev/null
+++ b/aos/vim/act.vim
@@ -0,0 +1,134 @@
+" Vim syntax file
+" Language: ACT c generation lang
+" Maintainer: FRC Team 971 <spartanrobotics.org>
+" Last Change: sometime
+
+" Quit when a (custom) syntax file was already loaded
+if exists("b:current_syntax")
+ finish
+endif
+
+syn keyword cTodo contained TODO FIXME XXX
+
+" It's easy to accidentally add a space after a backslash that was intended
+" for line continuation. Some compilers allow it, which makes it
+" unpredicatable and should be avoided.
+syn match cBadContinuation contained "\\\s\+$"
+
+" cCommentGroup allows adding matches for special things in comments
+syn cluster cCommentGroup contains=cTodo,cBadContinuation
+
+" This should be before cErrInParen to avoid problems with #define ({ xxx })
+if exists("c_curly_error")
+ syntax match cCurlyError "}"
+ syntax region cBlock start="{" end="}" contains=ALLBUT,cCurlyError,@cParenGroup,cErrInParen,cCppParen,cErrInBracket,cCppBracket,cCppString,@Spell fold
+else
+ syntax region cBlock start="{" end="}" transparent fold
+endif
+
+
+
+if exists("c_comment_strings")
+ " A comment can contain cString, cCharacter and cNumber.
+ " But a "*/" inside a cString in a cComment DOES end the comment! So we
+ " need to use a special type of cString: cCommentString, which also ends on
+ " "*/", and sees a "*" at the start of the line as comment again.
+ " Unfortunately this doesn't very well work for // type of comments :-(
+ syntax match cCommentSkip contained "^\s*\*\($\|\s\+\)"
+ syntax region cCommentString contained start=+L\=\\\@<!"+ skip=+\\\\\|\\"+ end=+"+ end=+\*/+me=s-1 contains=cSpecial,cCommentSkip
+ syntax region cComment2String contained start=+L\=\\\@<!"+ skip=+\\\\\|\\"+ end=+"+ end="$" contains=cSpecial
+ syntax region cCommentL start="//" skip="\\$" end="$" keepend contains=@cCommentGroup,cComment2String,cCharacter,cNumbersCom,cSpaceError,@Spell
+ if exists("c_no_comment_fold")
+ " Use "extend" here to have preprocessor lines not terminate halfway a
+ " comment.
+ syntax region cComment matchgroup=cCommentStart start="/\*" end="\*/" contains=@cCommentGroup,cCommentStartError,cCommentString,cCharacter,cNumbersCom,cSpaceError,@Spell extend
+ else
+ syntax region cComment matchgroup=cCommentStart start="/\*" end="\*/" contains=@cCommentGroup,cCommentStartError,cCommentString,cCharacter,cNumbersCom,cSpaceError,@Spell fold extend
+ endif
+else
+ syn region cCommentL start="//" skip="\\$" end="$" keepend contains=@cCommentGroup,cSpaceError,@Spell
+ if exists("c_no_comment_fold")
+ syn region cComment matchgroup=cCommentStart start="/\*" end="\*/" contains=@cCommentGroup,cCommentStartError,cSpaceError,@Spell extend
+ else
+ syn region cComment matchgroup=cCommentStart start="/\*" end="\*/" contains=@cCommentGroup,cCommentStartError,cSpaceError,@Spell fold extend
+ endif
+endif
+" keep a // comment separately, it terminates a preproc. conditional
+syntax match cCommentError display "\*/"
+syntax match cCommentStartError display "/\*"me=e-1 contained
+
+syn keyword cType int long short char void
+syn keyword cType signed unsigned float double
+if !exists("c_no_ansi") || exists("c_ansi_typedefs")
+ syn keyword cType size_t ssize_t off_t wchar_t ptrdiff_t sig_atomic_t fpos_t
+ syn keyword cType clock_t time_t va_list jmp_buf FILE DIR div_t ldiv_t
+ syn keyword cType mbstate_t wctrans_t wint_t wctype_t
+endif
+if !exists("c_no_c99") " ISO C99
+ syn keyword cType bool complex
+ syn keyword cType int8_t int16_t int32_t int64_t
+ syn keyword cType uint8_t uint16_t uint32_t uint64_t
+ syn keyword cType int_least8_t int_least16_t int_least32_t int_least64_t
+ syn keyword cType uint_least8_t uint_least16_t uint_least32_t uint_least64_t
+ syn keyword cType int_fast8_t int_fast16_t int_fast32_t int_fast64_t
+ syn keyword cType uint_fast8_t uint_fast16_t uint_fast32_t uint_fast64_t
+ syn keyword cType intptr_t uintptr_t
+ syn keyword cType intmax_t uintmax_t
+endif
+" syn keyword cStructure struct union enum typedef
+
+syn keyword cType args status action_name async_queue has priority
+
+
+" Define the default highlighting.
+" Only used when an item doesn't have highlighting yet
+hi def link cFormat cSpecial
+hi def link cCppString cString
+hi def link cCommentL cComment
+hi def link cCommentStart cComment
+hi def link cLabel Label
+hi def link cUserLabel Label
+hi def link cConditional Conditional
+hi def link cRepeat Repeat
+hi def link cCharacter Character
+hi def link cSpecialCharacter cSpecial
+hi def link cNumber Number
+hi def link cOctal Number
+hi def link cOctalZero PreProc " link this to Error if you want
+hi def link cFloat Float
+hi def link cOctalError cError
+hi def link cParenError cError
+hi def link cErrInParen cError
+hi def link cErrInBracket cError
+hi def link cCommentError cError
+hi def link cCommentStartError cError
+hi def link cSpaceError cError
+hi def link cSpecialError cError
+hi def link cCurlyError cError
+hi def link cOperator Operator
+hi def link cStructure Structure
+hi def link cStorageClass StorageClass
+hi def link cInclude Include
+hi def link cPreProc PreProc
+hi def link cDefine Macro
+hi def link cIncluded cString
+hi def link cError Error
+hi def link cStatement Statement
+hi def link cPreCondit PreCondit
+hi def link cType Type
+hi def link cConstant Constant
+hi def link cCommentString cString
+hi def link cComment2String cString
+hi def link cCommentSkip cComment
+hi def link cString String
+hi def link cComment Comment
+hi def link cSpecial SpecialChar
+hi def link cTodo Todo
+hi def link cBadContinuation Error
+hi def link cCppSkip cCppOut
+hi def link cCppOut2 cCppOut
+hi def link cCppOut Comment
+
+let b:current_syntax = "act"
+
+" vim: ts=8
diff --git a/frc971/atom_code/atom_code.gyp b/frc971/atom_code/atom_code.gyp
new file mode 100644
index 0000000..d727036
--- /dev/null
+++ b/frc971/atom_code/atom_code.gyp
@@ -0,0 +1,28 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'All',
+ 'type': 'none',
+ 'dependencies': [
+ '<(AOS)/build/aos_all.gyp:Atom',
+ '../control_loops/control_loops.gyp:DriveTrain',
+ '../input/input.gyp:JoystickReader',
+ '../input/input.gyp:SensorReader',
+ '../input/input.gyp:GyroReader',
+ '../input/input.gyp:AutoMode',
+ '../output/output.gyp:MotorWriter',
+ '../output/output.gyp:CameraServer',
+ 'camera/camera.gyp:frc971',
+ ],
+ 'copies': [
+ {
+ 'destination': '<(rsync_dir)',
+ 'files': [
+ 'scripts/aos_module.ko',
+ 'scripts/start_list.txt',
+ ],
+ },
+ ],
+ },
+ ],
+}
diff --git a/frc971/atom_code/build.sh b/frc971/atom_code/build.sh
new file mode 100755
index 0000000..d1dff19
--- /dev/null
+++ b/frc971/atom_code/build.sh
@@ -0,0 +1,3 @@
+#!/bin/bash
+
+../../aos/build/build.sh atom atom_code.gyp no $1
diff --git a/frc971/atom_code/camera/camera.gyp b/frc971/atom_code/camera/camera.gyp
new file mode 100644
index 0000000..6dc9530
--- /dev/null
+++ b/frc971/atom_code/camera/camera.gyp
@@ -0,0 +1,30 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'frc971_camera',
+ 'variables': {
+ 'srcdirs': ['.'],
+ 'manifest': 'frc971_camera.mf',
+ },
+ 'dependencies': [
+ '<(AOS)/atom_code/camera/camera.gyp:aos_camera',
+ '<(DEPTH)/frc971/queues/queues.gyp:frc971_queues_so',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/atom_code/camera/camera.gyp:aos_camera',
+ '<(DEPTH)/frc971/queues/queues.gyp:frc971_queues_so',
+ ],
+ 'includes': ['../../../aos/build/java.gypi'],
+ },
+ {
+ 'target_name': 'frc971',
+ 'variables': {
+ 'main_jar': 'frc971_camera',
+ },
+ 'dependencies': [
+ 'frc971_camera',
+ ],
+ 'includes': ['../../../aos/build/onejar.gypi'],
+ },
+ ],
+}
diff --git a/frc971/atom_code/camera/frc971_camera.mf b/frc971/atom_code/camera/frc971_camera.mf
new file mode 100644
index 0000000..e3929a2
--- /dev/null
+++ b/frc971/atom_code/camera/frc971_camera.mf
@@ -0,0 +1,2 @@
+Main-Class: org.spartanrobotics.camera.Test
+
diff --git a/frc971/atom_code/camera/org/spartanrobotics/camera/QueueReader.java b/frc971/atom_code/camera/org/spartanrobotics/camera/QueueReader.java
new file mode 100644
index 0000000..347b0c2
--- /dev/null
+++ b/frc971/atom_code/camera/org/spartanrobotics/camera/QueueReader.java
@@ -0,0 +1,16 @@
+package org.spartanrobotics.camera;
+
+import aos.NativeLoader;
+import aos.QueueLogHandler;
+import frc971.control_loops.Piston_q;
+
+public class QueueReader {
+
+ public static void main(String[] args) {
+ QueueLogHandler.UseForAll();
+ NativeLoader.load("frc971_queues_so");
+ System.out.println(Piston_q.shifters.FetchLatest());
+ System.out.println(Piston_q.shifters.getSet());
+ }
+
+}
diff --git a/frc971/atom_code/camera/org/spartanrobotics/camera/QueueTest.java b/frc971/atom_code/camera/org/spartanrobotics/camera/QueueTest.java
new file mode 100644
index 0000000..a71f447
--- /dev/null
+++ b/frc971/atom_code/camera/org/spartanrobotics/camera/QueueTest.java
@@ -0,0 +1,15 @@
+package org.spartanrobotics.camera;
+
+import aos.NativeLoader;
+import aos.QueueLogHandler;
+import frc971.control_loops.Piston_q;
+
+public class QueueTest {
+
+ public static void main(String[] args) {
+ QueueLogHandler.UseForAll();
+ NativeLoader.load("frc971_queues_so");
+ Piston_q.shifters.SafeMakeWithBuilder().set(false).Send();
+ }
+
+}
diff --git a/frc971/atom_code/camera/org/spartanrobotics/camera/Test.java b/frc971/atom_code/camera/org/spartanrobotics/camera/Test.java
new file mode 100644
index 0000000..86c06bc
--- /dev/null
+++ b/frc971/atom_code/camera/org/spartanrobotics/camera/Test.java
@@ -0,0 +1,44 @@
+package org.spartanrobotics.camera;
+
+import java.io.IOException;
+import com.googlecode.javacv.cpp.opencv_core;
+import com.googlecode.javacv.cpp.opencv_core.CvPoint;
+import com.googlecode.javacv.cpp.opencv_core.CvScalar;
+import com.googlecode.javacv.cpp.opencv_core.IplImage;
+import com.googlecode.javacv.cpp.opencv_imgproc;
+
+import aos.CameraProcessor;
+import aos.DebugServer;
+import aos.ImageGetter;
+import aos.ServableImage;
+import aos.Thresholder;
+
+public class Test extends CameraProcessor {
+ private final DebugServer server = new DebugServer(9719);
+ private final IplImage hsv = IplImage.create(ImageGetter.width, ImageGetter.height, opencv_core.IPL_DEPTH_8U, 3);
+ private final ServableImage thresholded = new ServableImage(ImageGetter.width, ImageGetter.height, opencv_core.IPL_DEPTH_8U, 1);
+
+ private Test(String[] args) throws IOException {
+ super(args);
+
+ server.addImage("/start", start);
+ server.addImage("/thresholded", thresholded, new DebugServer.Palette().add(0, 0, 0, 0).add(0, 0xFF, 0, 0xFF).add(0, 0, 0xFF, 0xFF));
+ }
+
+ @Override
+ protected void RunIteration() {
+ server.setTimestamp(getter.getTimestamp());
+
+ opencv_imgproc.cvCvtColor(start.getImage(), hsv, opencv_imgproc.CV_RGB2HSV);
+ Thresholder.threshold(hsv, thresholded.getImage(), 0, 100, 160, 0, 255, 0, 255);
+ thresholded.recordSnapshot(1);
+ if (thresholded.isDebugging()) {
+ opencv_core.cvCircle(thresholded.getImage(), new CvPoint(200, 200), 50, new CvScalar(2, 2, 2, 2), 5, 8, 0);
+ }
+ thresholded.releaseImage();
+ }
+
+ public static void main(String[] args) throws IOException {
+ new Test(args).Run();
+ }
+}
diff --git a/frc971/atom_code/scripts/aos_module.ko b/frc971/atom_code/scripts/aos_module.ko
new file mode 100644
index 0000000..cdaddb7
--- /dev/null
+++ b/frc971/atom_code/scripts/aos_module.ko
Binary files differ
diff --git a/frc971/atom_code/scripts/start_list.txt b/frc971/atom_code/scripts/start_list.txt
new file mode 100644
index 0000000..6bbcd70
--- /dev/null
+++ b/frc971/atom_code/scripts/start_list.txt
@@ -0,0 +1,15 @@
+MotorWriter
+JoystickReader
+SensorReader
+GyroReader
+DriveTrain
+WristMotor
+IntakeRollers
+HorizontalRoller
+VerticalRoller
+AutoMode
+BinaryLogReader
+CRIOLogReader
+CameraReader
+CameraServer
+CameraHTTPStreamer
diff --git a/frc971/constants.cpp b/frc971/constants.cpp
new file mode 100644
index 0000000..6c16097
--- /dev/null
+++ b/frc971/constants.cpp
@@ -0,0 +1,75 @@
+#include "frc971/constants.h"
+
+#include <stddef.h>
+#include <inttypes.h>
+
+#include "aos/common/messages/RobotState.q.h"
+#include "aos/atom_code/output/MotorOutput.h"
+
+namespace frc971 {
+namespace constants {
+
+namespace {
+
+const double kCompHorizontal = -1.77635 + 0.180;
+const double kPracticeHorizontal = -1.77635 + -0.073631;
+const int kCompCameraCenter = -2;
+const int kPracticeCameraCenter = -5;
+
+struct Values {
+ // what horizontal_offset returns
+ double horizontal;
+ // what camera_center returns
+ int camera_center;
+ // what drivetrain_motor_controllers returns
+ char drivetrain_controllers;
+};
+Values *values = NULL;
+// Attempts to retrieve a new Values instance and stores it in values if
+// necessary.
+// Returns a valid Values instance or NULL.
+const Values *GetValues() {
+ if (values == NULL) {
+ LOG(INFO, "creating a Constants for team %"PRIu16"\n",
+ aos::robot_state->team_id);
+ switch (aos::robot_state->team_id) {
+ case kCompTeamNumber:
+ values = new Values{kCompHorizontal, kCompCameraCenter,
+ aos::MotorOutput::TALON};
+ break;
+ case kPracticeTeamNumber:
+ values = new Values{kPracticeHorizontal, kPracticeCameraCenter,
+ aos::MotorOutput::VICTOR};
+ break;
+ default:
+ LOG(ERROR, "unknown team #%"PRIu16"\n",
+ aos::robot_state->team_id);
+ return NULL;
+ }
+ }
+ return values;
+}
+
+} // namespace
+
+bool horizontal_offset(double *horizontal) {
+ const Values *const values = GetValues();
+ if (values == NULL) return false;
+ *horizontal = values->horizontal;
+ return true;
+}
+bool camera_center(int *center) {
+ const Values *const values = GetValues();
+ if (values == NULL) return false;
+ *center = values->camera_center;
+ return true;
+}
+bool drivetrain_motor_controllers(char *controllers) {
+ const Values *const values = GetValues();
+ if (values == NULL) return false;
+ *controllers = values->drivetrain_controllers;
+ return true;
+}
+
+} // namespace constants
+} // namespace frc971
diff --git a/frc971/constants.h b/frc971/constants.h
new file mode 100644
index 0000000..ab360e0
--- /dev/null
+++ b/frc971/constants.h
@@ -0,0 +1,29 @@
+#include <stdint.h>
+
+namespace frc971 {
+namespace constants {
+
+// Has all of the numbers that change for both robots and makes it easy to
+// retrieve the values for the current one.
+//
+// All of the public functions to retrieve various values take a pointer to
+// store their output value into and assume that aos::robot_state->get() is
+// not null and is correct. They return true on success.
+
+const uint16_t kCompTeamNumber = 971;
+const uint16_t kPracticeTeamNumber = 5971;
+
+// Sets *horizontal to how many radians from the hall effect transition point
+// to horizontal for the wrist.
+bool horizontal_offset(double *horizontal);
+// Sets *center to how many pixels off center the vertical line
+// on the camera view is.
+bool camera_center(int *center);
+// Sets *talons to whether or not the drivetrain is using talons (otherwise it's
+// using victors).
+// Sets *controllers to what type of motor controllers to use for the drivetrain
+// (one of MotorOutput's constants).
+bool drivetrain_motor_controllers(char *controllers);
+
+} // namespace constants
+} // namespace frc971
diff --git a/frc971/control_loops/DriveTrain.cc b/frc971/control_loops/DriveTrain.cc
new file mode 100644
index 0000000..b627cc0
--- /dev/null
+++ b/frc971/control_loops/DriveTrain.cc
@@ -0,0 +1,298 @@
+#include "frc971/control_loops/DriveTrain.h"
+
+#include <stdio.h>
+#include <sched.h>
+#include <cmath>
+
+#include "aos/aos_core.h"
+#include "aos/common/logging/logging.h"
+#include "aos/common/queue.h"
+#include "frc971/control_loops/DriveTrain.mat"
+#include "frc971/control_loops/DriveTrain.q.h"
+#include "frc971/queues/GyroAngle.q.h"
+#include "frc971/queues/Piston.q.h"
+
+using frc971::sensors::gyro;
+
+namespace frc971 {
+namespace control_loops {
+
+// Width of the robot.
+const double width = 22.0 / 100.0 * 2.54;
+
+class DrivetrainMotorsSS : public MatrixClass {
+ public:
+ DrivetrainMotorsSS (void) {
+ MATRIX_INIT;
+ _offset = 0;
+ _integral_offset = 0;
+ _left_goal = 0.0;
+ _right_goal = 0.0;
+ _raw_left = 0.0;
+ _raw_right = 0.0;
+ }
+ void SetGoal(double left, double left_velocity, double right, double right_velocity) {
+ _left_goal = left;
+ _right_goal = right;
+ R << left + _integral_offset * width / 2.0, left_velocity, right - _integral_offset * width / 2.0, right_velocity;
+ }
+ void SetRawPosition(double left, double right) {
+ _raw_right = right;
+ _raw_left = left;
+ Y << left + _offset + _integral_offset, right - _offset + _integral_offset;
+ }
+ void SetPosition(double left, double right, double gyro, bool control_loop_driving) {
+ // Decay the offset quickly because this gyro is great.
+ _offset = (0.25) * (right - left - gyro * width) / 2.0 + 0.75 * _offset;
+ const double angle_error = (_right_goal - _left_goal) / width - (_raw_right - _offset - _raw_left - _offset) / width;
+ if (!control_loop_driving) {
+ _integral_offset = 0.0;
+ } else if (std::abs(angle_error) < M_PI / 10.0) {
+ _integral_offset -= angle_error * 0.010;
+ } else {
+ _integral_offset *= 0.97;
+ }
+ _gyro = gyro;
+ SetRawPosition(left, right);
+ LOG(DEBUG, "Left %f->%f Right %f->%f Gyro %f aerror %f ioff %f\n", left + _offset, _left_goal, right - _offset, _right_goal, gyro, angle_error, _integral_offset);
+ }
+ double UnDeadband(double value) {
+ const double positive_deadband_power = 0.15 * 12;
+ const double negative_deadband_power = 0.09 * 12;
+ if (value > 0) {
+ value += positive_deadband_power;
+ }
+ if (value < 0) {
+ value -= negative_deadband_power;
+ }
+ if (value > 12.0) {
+ value = 12.0;
+ }
+ if (value < -12.0) {
+ value = -12.0;
+ }
+ return value;
+ }
+
+ void SendMotors(Drivetrain::Output *status) {
+ status->left_voltage = UnDeadband(U[0]);
+ status->right_voltage = UnDeadband(U[1]);
+ }
+ void PrintMotors() const {
+ // LOG(DEBUG, "Left Power %f Right Power %f lg %f rg %f le %f re %f gyro %f\n", U[0], U[1], R[0], R[2], Y[0], Y[1], _gyro);
+ LOG(DEBUG, "lg %f rg %f le %f re %f gyro %f off %f\n", R[0], R[2], Y[0], Y[1], _gyro * 180.0 / M_PI, _offset);
+ }
+
+ private:
+ double _integral_offset;
+ double _offset;
+ double _gyro;
+ double _left_goal;
+ double _right_goal;
+ double _raw_left;
+ double _raw_right;
+};
+
+class DrivetrainMotorsOL {
+ public:
+ DrivetrainMotorsOL() {
+ _old_wheel = 0.0;
+ quick_stop_accumulator = 0.0;
+ _wheel = 0.0;
+ _throttle = 0.0;
+ _quickturn = false;
+ _highgear = true;
+ _neg_inertia_accumulator = 0.0;
+ _left_pwm = 0.0;
+ _right_pwm = 0.0;
+ }
+ void SetGoal(double wheel, double throttle, bool quickturn, bool highgear) {
+ _wheel = wheel;
+ _throttle = throttle;
+ _quickturn = quickturn;
+ _highgear = highgear;
+ _left_pwm = 0.0;
+ _right_pwm = 0.0;
+ }
+ void Update(void) {
+ double overPower;
+ float sensitivity = 1.7;
+ float angular_power;
+ float linear_power;
+ double wheel;
+
+ double neg_inertia = _wheel - _old_wheel;
+ _old_wheel = _wheel;
+
+ double wheelNonLinearity;
+ if (_highgear) {
+ wheelNonLinearity = 0.7; // used to be csvReader->TURN_NONLIN_HIGH
+ // Apply a sin function that's scaled to make it feel better.
+ const double angular_range = M_PI / 2.0 * wheelNonLinearity;
+ wheel = sin(angular_range * _wheel) / sin(angular_range);
+ wheel = sin(angular_range * _wheel) / sin(angular_range);
+ } else {
+ wheelNonLinearity = 0.4; // used to be csvReader->TURN_NONLIN_LOW
+ // Apply a sin function that's scaled to make it feel better.
+ const double angular_range = M_PI / 2.0 * wheelNonLinearity;
+ wheel = sin(angular_range * _wheel) / sin(angular_range);
+ wheel = sin(angular_range * _wheel) / sin(angular_range);
+ wheel = sin(angular_range * _wheel) / sin(angular_range);
+ }
+
+ double neg_inertia_scalar;
+ if (_highgear) {
+ neg_inertia_scalar = 20.0; // used to be csvReader->NEG_INTERTIA_HIGH
+ sensitivity = 1.22; // used to be csvReader->SENSE_HIGH
+ } else {
+ if (wheel * neg_inertia > 0) {
+ neg_inertia_scalar = 16; // used to be csvReader->NEG_INERTIA_LOW_MORE
+ } else {
+ if (fabs(wheel) > 0.65) {
+ neg_inertia_scalar = 16; // used to be csvReader->NEG_INTERTIA_LOW_LESS_EXT
+ } else {
+ neg_inertia_scalar = 5; // used to be csvReader->NEG_INTERTIA_LOW_LESS
+ }
+ }
+ sensitivity = 1.24; // used to be csvReader->SENSE_LOW
+
+ if (fabs(_throttle) > 0.1) { // used to be csvReader->SENSE_CUTTOFF
+ sensitivity = 1 - (1 - sensitivity) / fabs(_throttle);
+ }
+ }
+ double neg_inertia_power = neg_inertia * neg_inertia_scalar;
+ _neg_inertia_accumulator += neg_inertia_power;
+
+ wheel = wheel + _neg_inertia_accumulator;
+ if (_neg_inertia_accumulator > 1) {
+ _neg_inertia_accumulator -= 1;
+ } else if (_neg_inertia_accumulator < -1) {
+ _neg_inertia_accumulator += 1;
+ } else {
+ _neg_inertia_accumulator = 0;
+ }
+
+ linear_power = _throttle;
+
+ const double quickstop_scalar = 6;
+ if (_quickturn) {
+ double qt_angular_power = wheel;
+ const double alpha = 0.1;
+ if (fabs(linear_power) < 0.2) {
+ if (qt_angular_power > 1) qt_angular_power = 1.0;
+ if (qt_angular_power < -1) qt_angular_power = -1.0;
+ } else {
+ qt_angular_power = 0.0;
+ }
+ quick_stop_accumulator = (1 - alpha) * quick_stop_accumulator + alpha * qt_angular_power * quickstop_scalar;
+ overPower = 1.0;
+ if (_highgear) {
+ sensitivity = 1.0;
+ } else {
+ sensitivity = 1.0;
+ }
+ angular_power = wheel;
+ } else {
+ overPower = 0.0;
+ angular_power = fabs(_throttle) * wheel * sensitivity;
+ angular_power -= quick_stop_accumulator;
+ if (quick_stop_accumulator > 1) {
+ quick_stop_accumulator -= 1;
+ } else if (quick_stop_accumulator < -1) {
+ quick_stop_accumulator += 1;
+ } else {
+ quick_stop_accumulator = 0;
+ }
+ }
+
+ _right_pwm = _left_pwm = linear_power;
+ _left_pwm += angular_power;
+ _right_pwm -= angular_power;
+
+ if (_left_pwm > 1.0) {
+ _right_pwm -= overPower*(_left_pwm - 1.0);
+ _left_pwm = 1.0;
+ } else if (_right_pwm > 1.0) {
+ _left_pwm -= overPower*(_right_pwm - 1.0);
+ _right_pwm = 1.0;
+ } else if (_left_pwm < -1.0) {
+ _right_pwm += overPower*(-1.0 - _left_pwm);
+ _left_pwm = -1.0;
+ } else if (_right_pwm < -1.0) {
+ _left_pwm += overPower*(-1.0 - _right_pwm);
+ _right_pwm = -1.0;
+ }
+ }
+
+ void SendMotors(Drivetrain::Output *output) {
+ LOG(DEBUG, "left pwm: %f right pwm: %f wheel: %f throttle: %f, qa %f\n",
+ _left_pwm, _right_pwm, _wheel, _throttle, quick_stop_accumulator);
+ output->left_voltage = _left_pwm * 12.0;
+ output->right_voltage = _right_pwm * 12.0;
+ if (_highgear) {
+ shifters.MakeWithBuilder().set(false).Send();
+ } else {
+ shifters.MakeWithBuilder().set(true).Send();
+ }
+ }
+
+ private:
+ double _old_wheel;
+ double _wheel;
+ double _throttle;
+ bool _quickturn;
+ bool _highgear;
+ double _neg_inertia_accumulator;
+ double _left_pwm;
+ double _right_pwm;
+ double quick_stop_accumulator;
+};
+
+void DrivetrainLoop::RunIteration(const Drivetrain::Goal *goal,
+ const Drivetrain::Position *position,
+ Drivetrain::Output *output,
+ Drivetrain::Status * /*status*/) {
+ // TODO(aschuh): These should be members of the class.
+ static DrivetrainMotorsSS dt_closedloop;
+ static DrivetrainMotorsOL dt_openloop;
+
+ bool bad_pos = false;
+ if (position == NULL) {
+ LOG(WARNING, "no pos\n");
+ bad_pos = true;
+ }
+
+ double wheel = goal->steering;
+ double throttle = goal->throttle;
+ bool quickturn = goal->quickturn;
+ bool highgear = goal->highgear;
+
+ bool control_loop_driving = goal->control_loop_driving;
+ double left_goal = goal->left_goal;
+ double right_goal = goal->right_goal;
+
+ dt_closedloop.SetGoal(left_goal, 0.0, right_goal, 0.0);
+ if (!bad_pos) {
+ const double left_encoder = position->left_encoder;
+ const double right_encoder = position->right_encoder;
+ if (gyro.FetchLatest()) {
+ dt_closedloop.SetPosition(left_encoder, right_encoder,
+ gyro->angle, control_loop_driving);
+ } else {
+ dt_closedloop.SetRawPosition(left_encoder, right_encoder);
+ }
+ }
+ dt_closedloop.Update(!bad_pos, bad_pos || (output == NULL));
+ dt_openloop.SetGoal(wheel, throttle, quickturn, highgear);
+ dt_openloop.Update();
+ if (control_loop_driving) {
+ dt_closedloop.SendMotors(output);
+ } else {
+ dt_openloop.SendMotors(output);
+ }
+}
+
+} // namespace control_loops
+} // namespace frc971
+
+AOS_RUN_LOOP(frc971::control_loops::DrivetrainLoop)
diff --git a/frc971/control_loops/DriveTrain.h b/frc971/control_loops/DriveTrain.h
new file mode 100644
index 0000000..61ea524
--- /dev/null
+++ b/frc971/control_loops/DriveTrain.h
@@ -0,0 +1,32 @@
+#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
+#define FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
+
+#include "aos/common/control_loop/ControlLoop.h"
+#include "frc971/control_loops/DriveTrain.q.h"
+
+namespace frc971 {
+namespace control_loops {
+
+class DrivetrainLoop
+ : public aos::control_loops::ControlLoop<control_loops::Drivetrain> {
+ public:
+ // Constructs a control loop which can take a Drivetrain or defaults to the
+ // drivetrain at frc971::control_loops::drivetrain
+ explicit DrivetrainLoop(
+ control_loops::Drivetrain *my_drivetrain = &control_loops::drivetrain)
+ : aos::control_loops::ControlLoop<control_loops::Drivetrain>(
+ my_drivetrain) {}
+
+ protected:
+ // Executes one cycle of the control loop.
+ virtual void RunIteration(
+ const control_loops::Drivetrain::Goal *goal,
+ const control_loops::Drivetrain::Position *position,
+ control_loops::Drivetrain::Output *output,
+ control_loops::Drivetrain::Status *status);
+};
+
+} // namespace control_loops
+} // namespace frc971
+
+#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
diff --git a/frc971/control_loops/DriveTrain.mat b/frc971/control_loops/DriveTrain.mat
new file mode 100644
index 0000000..fcc6f45
--- /dev/null
+++ b/frc971/control_loops/DriveTrain.mat
@@ -0,0 +1,12 @@
+#include "frc971/control_loops/StateFeedbackLoop.h"
+
+typedef StateFeedbackLoop<4, 2> MatrixClass;
+#define MATRIX_INIT A << 1.0000000000, 0.0095410093, 0.0000000000, -0.0000167223, 0.0000000000, 0.9096302600, 0.0000000000, -0.0032396985, 0.0000000000, -0.0000167223, 1.0000000000, 0.0095410093, 0.0000000000, -0.0032396985, 0.0000000000, 0.9096302600; \
+B << 0.0000628338, 0.0000022892, 0.0123712263, 0.0004435007, 0.0000022892, 0.0000628338, 0.0004435007, 0.0123712263; \
+C << 1.0000000000, 0.0000000000, 0.0000000000, 0.0000000000, 0.0000000000, 0.0000000000, 1.0000000000, 0.0000000000; \
+D << 0.0000000000, 0.0000000000, 0.0000000000, 0.0000000000; \
+L << 1.7496302600, -0.0032396985, 72.1296388532, -0.4369906587, -0.0032396985, 1.7496302600, -0.4369906586, 72.1296388532; \
+K << 242.8102455120, 19.7898401032, -8.7045950610, -0.9720464423, -8.7045950610, -0.9720464423, 242.8102455120, 19.7898401032; \
+U_max << 12.0000000000, 12.0000000000; \
+U_min << -12.0000000000, -12.0000000000; \
+
diff --git a/frc971/control_loops/DriveTrain.q b/frc971/control_loops/DriveTrain.q
new file mode 100644
index 0000000..f56c115
--- /dev/null
+++ b/frc971/control_loops/DriveTrain.q
@@ -0,0 +1,38 @@
+package frc971.control_loops;
+
+import "aos/common/control_loop/control_loops.q";
+
+queue_group Drivetrain {
+ implements aos.control_loops.ControlLoop;
+
+ message Goal {
+ float steering;
+ float throttle;
+ bool highgear;
+ bool quickturn;
+ bool control_loop_driving;
+ float left_goal;
+ float right_goal;
+ };
+
+ message Position {
+ double left_encoder;
+ double right_encoder;
+ };
+
+ message Output {
+ float left_voltage;
+ float right_voltage;
+ };
+
+ message Status {
+ bool is_done;
+ };
+
+ queue Goal goal;
+ queue Position position;
+ queue Output output;
+ queue Status status;
+};
+
+queue_group Drivetrain drivetrain;
diff --git a/frc971/control_loops/StateFeedbackLoop.h b/frc971/control_loops/StateFeedbackLoop.h
new file mode 100644
index 0000000..ad37f49
--- /dev/null
+++ b/frc971/control_loops/StateFeedbackLoop.h
@@ -0,0 +1,131 @@
+#ifndef FRC971_CONTROL_LOOPS_STATEFEEDBACKLOOP_H_
+#define FRC971_CONTROL_LOOPS_STATEFEEDBACKLOOP_H_
+
+// wikipedia article is <http://en.wikipedia.org/wiki/State_observer>
+
+#include "Eigen/Dense"
+
+template <int number_of_states, int number_of_outputs>
+class StateFeedbackPlant {
+ public:
+ Eigen::Matrix<double, number_of_states, 1> X;
+ Eigen::Matrix<double, number_of_outputs, 1> Y;
+ Eigen::Matrix<double, number_of_outputs, 1> U;
+ Eigen::Matrix<double, number_of_outputs, 1> U_max;
+ Eigen::Matrix<double, number_of_outputs, 1> U_min;
+ Eigen::Matrix<double, number_of_states, number_of_states> A;
+ Eigen::Matrix<double, number_of_states, number_of_outputs> B;
+ Eigen::Matrix<double, number_of_outputs, number_of_states> C;
+ Eigen::Matrix<double, number_of_outputs, number_of_outputs> D;
+ // TODO(aschuh): These following 2 lines are here because MATRIX_INIT
+ // assumes that you have a controller as well as a plant.
+ Eigen::Matrix<double, number_of_states, number_of_outputs> L;
+ Eigen::Matrix<double, number_of_outputs, number_of_states> K;
+
+ StateFeedbackPlant() {
+ X.setZero();
+ Y.setZero();
+ U.setZero();
+ }
+
+ virtual ~StateFeedbackPlant() {}
+
+ // If U is outside the hardware range, limit it before the plant tries to use
+ // it.
+ virtual void CapU() {
+ for (int i = 0; i < number_of_outputs; ++i) {
+ if (U[i] > U_max[i]) {
+ U[i] = U_max[i];
+ } else if (U[i] < U_min[i]) {
+ U[i] = U_min[i];
+ }
+ }
+ }
+ // Computes the new X and Y given the control input.
+ void Update() {
+ CapU();
+ X = A * X + B * U;
+ Y = C * X + D * U;
+ }
+
+ protected:
+ // these are accessible from non-templated subclasses
+ static const int number_of_states_var = number_of_states;
+ static const int number_of_outputs_var = number_of_outputs;
+};
+
+template <int number_of_states, int number_of_outputs>
+class StateFeedbackLoop {
+ public:
+ Eigen::Matrix<double, number_of_states, 1> X;
+ Eigen::Matrix<double, number_of_states, 1> X_hat;
+ Eigen::Matrix<double, number_of_outputs, 1> Y;
+ Eigen::Matrix<double, number_of_states, 1> R;
+ Eigen::Matrix<double, number_of_outputs, 1> U;
+ Eigen::Matrix<double, number_of_outputs, 1> U_max;
+ Eigen::Matrix<double, number_of_outputs, 1> U_min;
+ Eigen::Matrix<double, number_of_outputs, 1> U_ff;
+ Eigen::Matrix<double, number_of_states, number_of_states> A;
+ Eigen::Matrix<double, number_of_states, number_of_outputs> B;
+ // K in wikipedia article
+ Eigen::Matrix<double, number_of_outputs, number_of_states> C;
+ Eigen::Matrix<double, number_of_outputs, number_of_outputs> D;
+ // B in wikipedia article
+ Eigen::Matrix<double, number_of_states, number_of_outputs> L;
+ // C in wikipedia article
+ Eigen::Matrix<double, number_of_outputs, number_of_states> K;
+
+ StateFeedbackLoop() {
+ // You have to initialize all the matrices to 0 or else all their elements
+ // are undefined.
+ X.setZero();
+ X_hat.setZero();
+ Y.setZero();
+ R.setZero();
+ U.setZero();
+ U_ff.setZero();
+ }
+ virtual ~StateFeedbackLoop() {}
+
+ virtual void FeedForward() {
+ for (int i = 0; i < number_of_outputs; ++i) {
+ U_ff[i] = 0.0;
+ }
+ }
+ // If U is outside the hardware range, limit it before it
+ // gets added to the observer.
+ virtual void CapU() {
+ for (int i = 0; i < number_of_outputs; ++i) {
+ if (U[i] > U_max[i]) {
+ U[i] = U_max[i];
+ } else if (U[i] < U_min[i]) {
+ U[i] = U_min[i];
+ }
+ }
+ }
+ // update_observer is whether or not to use the values in Y.
+ // stop_motors is whether or not to output all 0s.
+ void Update(bool update_observer, bool stop_motors) {
+ if (stop_motors) {
+ for (int i = 0; i < number_of_outputs; ++i) {
+ U[i] = 0.0;
+ }
+ } else {
+ // new power = constant * (goal - current prediction)
+ U.noalias() = K * (R - X_hat);
+ CapU();
+ }
+
+ if (update_observer) {
+ X_hat = (A - L * C) * X_hat + L * Y + B * U;
+ } else {
+ X_hat = A * X_hat + B * U;
+ }
+ }
+
+ protected:
+ // these are accessible from non-templated subclasses
+ static const int number_of_states_var = number_of_states;
+ static const int number_of_outputs_var = number_of_outputs;
+};
+#endif // FRC971_CONTROL_LOOPS_STATEFEEDBACKLOOP_H_
diff --git a/frc971/control_loops/control_loops.gyp b/frc971/control_loops/control_loops.gyp
new file mode 100644
index 0000000..a9ddb12
--- /dev/null
+++ b/frc971/control_loops/control_loops.gyp
@@ -0,0 +1,43 @@
+{
+ 'variables': {
+ 'loop_files': [
+ 'DriveTrain.q',
+ ]
+ },
+ 'targets': [
+ {
+ 'target_name': 'control_loops',
+ 'type': 'static_library',
+ 'sources': ['<@(loop_files)'],
+ 'variables': {
+ 'header_path': 'frc971/control_loops',
+ },
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(AOS)/common/common.gyp:control_loop_queues',
+ '<(AOS)/common/common.gyp:queues',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(AOS)/common/common.gyp:control_loop_queues',
+ '<(AOS)/common/common.gyp:queues',
+ ],
+ 'includes': ['../../aos/build/queues.gypi'],
+ },
+ {
+ 'target_name': 'DriveTrain',
+ 'type': 'executable',
+ 'sources': [
+ 'DriveTrain.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:logging',
+ '<(AOS)/common/common.gyp:controls',
+ '<(AOS)/build/aos.gyp:libaos',
+ 'control_loops',
+ '<(DEPTH)/frc971/queues/queues.gyp:queues',
+ '<(EXTERNALS):eigen',
+ ],
+ },
+ ],
+}
diff --git a/frc971/control_loops/matlab/drivetrain_controller.m b/frc971/control_loops/matlab/drivetrain_controller.m
new file mode 100644
index 0000000..11a5a4b
--- /dev/null
+++ b/frc971/control_loops/matlab/drivetrain_controller.m
@@ -0,0 +1,231 @@
+close all;
+load 'drivetrain_spin_low'
+load 'drivetrain_strait_low'
+m = 68;
+rb = 0.617998644 / 2.0;
+J = 7;
+stall_current = 133.0;
+R = 12.0 / stall_current / 4 / 0.43;
+Km = (12.0 - R * 2.7) / (4650.0 / 60.0 * 2.0 * pi);
+Kt = 0.008;
+r = 0.04445; % 3.5 inches diameter
+G_low = 60.0 / 15.0 * 50.0 / 15.0;
+G_high = 45.0 / 30.0 * 50.0 / 15.0;
+dt = 0.01;
+
+G = G_low;
+
+msp = (1.0 / m + rb ^ 2.0 / J);
+msn = (1.0 / m - rb ^ 2.0 / J);
+tc = -Km * Kt * G ^ 2.0 / (R * r ^ 2.0);
+mp = G * Kt / (R * r);
+
+A = [0 1 0 0; 0 msp*tc 0 msn*tc; 0 0 0 1; 0 msn*tc 0 msp*tc];
+B = [0 0; msp * mp msn * mp; 0 0; msn * mp msp * mp];
+C = [1 0 0 0; 0 0 1 0];
+D = [0 0; 0 0];
+
+dm = c2d(ss(A, B, C, D), dt);
+
+hp = .8;
+lp = .85;
+K = place(dm.a, dm.b, [hp, hp, lp, lp]);
+
+hlp = 0.07;
+llp = 0.09;
+L = place(dm.a', dm.c', [hlp, hlp, llp, llp])';
+
+% Plot what we computed
+
+fd = fopen('/home/aschuh/frc971/2012/trunk/src/atom_code/control_loops/Drivetrain.mat', 'w');
+n = 1;
+sm = [];
+writeMatHeader(fd, size(dm.a, 1), size(dm.b, 2));
+writeMat(fd, dm.a, 'A');
+writeMat(fd, dm.b, 'B');
+writeMat(fd, dm.c, 'C');
+writeMat(fd, dm.d, 'D');
+writeMat(fd, L, 'L');
+writeMat(fd, K, 'K');
+writeMat(fd, [12; 12], 'U_max');
+writeMat(fd, [-12; -12], 'U_min');
+writeMatFooter(fd);
+fclose(fd);
+
+full_model = dss([dm.a (-dm.b * K); eye(4) (dm.a - dm.b * K - L * dm.c)], [0, 0; 0, 0; 0, 0; 0, 0; L], [C, [0, 0, 0, 0; 0, 0, 0, 0]], 0, eye(8), 0.01);
+
+n = 1;
+sm_strait = [];
+t = drivetrain_strait_low(1, 1) + dt * (n - 1);
+x = [drivetrain_strait_low(1, 2); 0; drivetrain_strait_low(1, 3); 0];
+while t < drivetrain_strait_low(end, 1)
+ sm_strait(n, 1) = t;
+ sm_strait(n, 2) = (x(1,1) + x(3,1)) / 2.0;
+ t = t + dt;
+ x = dm.a * x + dm.b * [drivetrain_strait_low(n, 4); drivetrain_strait_low(n, 5)];
+ n = n + 1;
+end
+
+figure;
+plot(drivetrain_strait_low(:, 1), (drivetrain_strait_low(:, 2) + drivetrain_strait_low(:, 3)) / 2.0, sm_strait(:, 1), sm_strait(:, 2));
+legend('actual', 'sim');
+
+n = 1;
+sm_spin = [];
+t = drivetrain_spin_low(1, 1) + dt * (n - 1);
+x = [drivetrain_spin_low(1, 2); 0; drivetrain_spin_low(1, 3); 0];
+while t < drivetrain_spin_low(end, 1)
+ sm_spin(n, 1) = t;
+ sm_spin(n, 2) = (x(1,1) - x(3,1)) / 2.0;
+ t = t + dt;
+ x = dm.a * x + dm.b * [drivetrain_spin_low(n, 4); drivetrain_spin_low(n, 5)];
+ n = n + 1;
+end
+
+figure;
+plot(drivetrain_spin_low(:, 1), (drivetrain_spin_low(:, 2) - drivetrain_spin_low(:, 3)) / 2.0, sm_spin(:, 1), sm_spin(:, 2));
+legend('actual', 'sim');
+
+%figure;
+%nyquist(full_model);
+
+
+%%
+t = 0;
+x = [0; 0; 0; 0;];
+while t < logging(end, 1)
+ sm(n, 1) = t;
+ sm(n, 2) = x(1,1);
+ sm(n, 3) = x(3,1);
+ t = t + dt;
+ x = dm.a * x + dm.b * [12.0; 12.0];
+ n = n + 1;
+end
+
+figure;
+plot(logging(:, 1), logging(:, 2), sm(:, 1), sm(:, 2));
+legend('actual', 'sim');
+
+%% Simulation of a small turn angle with a large distance to travel
+tf = 2;
+x = [0; 0; 0.1; 0;];
+r = [10; 0; 10; 0];
+
+smt = zeros(tf / dt, 8);
+t = 0;
+xhat = x;
+n = 1;
+% 1 means scale
+% 2 means just limit to 12 volts
+% 3 means preserve the difference in power
+captype = 1;
+while n <= size(smt, 1)
+ smt(n, 1) = t;
+ smt(n, 2) = x(1,1);
+ smt(n, 3) = x(3,1);
+ t = t + dt;
+
+ u = K * (r - xhat);
+ smt(n, 4) = u(1,1);
+ smt(n, 5) = u(2,1);
+
+ if captype == 1
+ if sum(abs(u) > 12.0)
+ % We have a problem!
+ % Check to see if it's a big steering power problem,
+ % or a big drive error.
+ turnPower = (u(1, 1) - u(2, 1));
+ drivePower = (u(1, 1) + u(2, 1));
+ scaleFactor = 12.0 / max(abs(u));
+ smt(n, 8) = 1.0 / scaleFactor;
+ % Only start scaling the turn power up if we are far out of
+ % range.
+ if abs(turnPower) < 0.5 * abs(drivePower)
+ % Turn power is swamped.
+ deltaTurn = turnPower / 2.0 / scaleFactor * 0.5;
+ u(1, 1) = u(1, 1) + deltaTurn;
+ u(2, 1) = u(2, 1) - deltaTurn;
+ scaleFactor = 12.0 / max(abs(u));
+ else
+ if 0.5 * abs(turnPower) > abs(drivePower)
+ % Drive power is swamped.
+ deltaDrive = drivePower / 2.0 / scaleFactor * 0.5;
+ u(1, 1) = u(1, 1) + deltaDrive;
+ u(2, 1) = u(2, 1) + deltaDrive;
+ scaleFactor = 12.0 / max(abs(u));
+ end
+ end
+ u = u * scaleFactor;
+ end
+ else
+ if captype == 2
+ if u(1, 1) > 12.0
+ u(1, 1) = 12.0;
+ end
+ if u(1, 1) < -12.0
+ u(1, 1) = -12.0;
+ end
+ if u(2, 1) > 12.0
+ u(2, 1) = 12.0;
+ end
+ if u(2, 1) < -12.0
+ u(2, 1) = -12.0;
+ end
+ else
+ if captype == 3
+ if u(1, 1) > 12.0
+ u(2, 1) = u(2, 1) - (u(1, 1) - 12.0);
+ else
+ if u(1, 1) < -12.0
+ u(2, 1) = u(2, 1) - (u(1, 1) + 12.0);
+ end
+ end
+ if u(2, 1) > 12.0
+ u(1, 1) = u(1, 1) - (u(2, 1) - 12.0);
+ else
+ if u(2, 1) < -12.0
+ u(1, 1) = u(1, 1) - (u(2, 1) + 12.0);
+ end
+ end
+ if u(1, 1) > 12.0
+ u(1, 1) = 12.0;
+ end
+ if u(1, 1) < -12.0
+ u(1, 1) = -12.0;
+ end
+ if u(2, 1) > 12.0
+ u(2, 1) = 12.0;
+ end
+ if u(2, 1) < -12.0
+ u(2, 1) = -12.0;
+ end
+ end
+ end
+
+ end
+ smt(n, 6) = u(1,1);
+ smt(n, 7) = u(2,1);
+ xhat = dm.a * xhat + dm.b * u + L * (dm.c * x - dm.c * xhat);
+ x = dm.a * x + dm.b * u;
+
+ n = n + 1;
+end
+
+figure;
+subplot(6, 1, 1);
+plot(smt(:, 1), smt(:, 2) + smt(:, 3));
+legend('dist');
+subplot(6, 1, 2);
+plot(smt(:, 1), smt(:, 2) - smt(:, 3));
+legend('angle');
+subplot(3, 1, 2);
+plot(smt(:, 1), smt(:, 4), smt(:, 1), smt(:, 5));
+legend('lu', 'ru');
+subplot(3, 1, 3);
+plot(smt(:, 1), smt(:, 6), smt(:, 1), smt(:, 7));
+legend('lu_{real}', 'ru_{real}');
+
+%figure;
+%plot(smt(:, 1), smt(:, 8))
+%legend('Scale Factor');
+
diff --git a/frc971/control_loops/matlab/drivetrain_spin_fast.csv b/frc971/control_loops/matlab/drivetrain_spin_fast.csv
new file mode 100644
index 0000000..5768209
--- /dev/null
+++ b/frc971/control_loops/matlab/drivetrain_spin_fast.csv
@@ -0,0 +1,215 @@
+12038,8.037056,-7.571709,1.000000
+12039,8.037056,-7.571709,1.000000
+12040,8.037056,-7.571709,1.000000
+12041,8.037254,-7.572700,1.000000
+12042,8.044792,-7.577064,1.000000
+12043,8.053718,-7.583610,1.000000
+12044,8.066016,-7.593330,1.000000
+12045,8.078909,-7.602652,1.000000
+12046,8.094183,-7.613760,1.000000
+12047,8.109655,-7.624670,1.000000
+12048,8.126118,-7.637167,1.000000
+12049,8.141789,-7.650060,1.000000
+12050,8.156070,-7.662556,1.000000
+12051,8.174716,-7.677433,1.000000
+12052,8.190188,-7.690128,1.000000
+12053,8.208635,-7.704608,1.000000
+12054,8.225694,-7.717303,1.000000
+12055,8.242951,-7.729800,1.000000
+12056,8.261200,-7.745073,1.000000
+12057,8.276077,-7.758363,1.000000
+12058,8.289565,-7.771058,1.000000
+12059,8.308012,-7.787720,1.000000
+12060,8.327253,-7.805771,1.000000
+12061,8.345105,-7.819457,1.000000
+12062,8.360379,-7.830565,1.000000
+12063,8.377041,-7.844252,1.000000
+12064,8.396083,-7.860914,1.000000
+12065,8.413539,-7.877378,1.000000
+12066,8.430597,-7.895230,1.000000
+12067,8.445871,-7.910107,1.000000
+12068,8.460153,-7.923397,1.000000
+12069,8.478600,-7.938274,1.000000
+12070,8.497444,-7.954341,1.000000
+12071,8.516288,-7.970408,1.000000
+12072,8.535132,-7.987268,1.000000
+12073,8.549215,-8.002541,1.000000
+12074,8.563299,-8.018410,1.000000
+12075,8.581944,-8.037651,1.000000
+12076,8.605152,-8.057288,1.000000
+12077,8.623203,-8.070578,1.000000
+12078,8.639865,-8.087637,1.000000
+12079,8.658709,-8.105489,1.000000
+12080,8.676958,-8.122945,1.000000
+12087,8.815213,-8.259811,1.000000
+12088,8.835247,-8.279250,1.000000
+12089,8.852702,-8.298094,1.000000
+12090,8.876307,-8.320310,1.000000
+12091,8.897333,-8.338758,1.000000
+12092,8.922921,-8.360577,1.000000
+12093,8.948311,-8.383983,1.000000
+12094,8.968147,-8.403621,1.000000
+12095,8.988974,-8.426035,1.000000
+12096,9.009405,-8.447656,1.000000
+12097,9.035191,-8.474633,1.000000
+12098,9.055027,-8.494865,1.000000
+12099,9.076450,-8.516288,1.000000
+12100,9.101641,-8.540686,1.000000
+12101,9.121675,-8.560323,1.000000
+12102,9.144090,-8.583729,1.000000
+12103,9.171066,-8.609119,1.000000
+12104,9.195663,-8.630542,1.000000
+12105,9.218672,-8.653155,1.000000
+12106,9.240690,-8.671602,1.000000
+12107,9.265881,-8.693421,1.000000
+12108,9.290676,-8.717621,1.000000
+12109,9.315868,-8.741424,1.000000
+12110,9.343043,-8.767210,1.000000
+12111,9.365655,-8.788038,1.000000
+12112,9.392632,-8.813626,1.000000
+12113,9.417427,-8.836635,1.000000
+12114,9.441230,-8.857066,1.000000
+12115,9.468801,-8.881464,1.000000
+12116,9.499150,-8.906656,1.000000
+12117,9.521564,-8.928475,1.000000
+12118,9.551120,-8.953666,1.000000
+12119,9.574724,-8.974692,1.000000
+12120,9.604081,-9.003454,1.000000
+12121,9.631455,-9.030629,1.000000
+12122,9.656646,-9.054829,1.000000
+12123,9.686400,-9.084979,1.000000
+12124,9.711789,-9.111559,1.000000
+12125,9.737576,-9.136552,1.000000
+12126,9.761776,-9.158570,1.000000
+12127,9.788554,-9.182770,1.000000
+12128,9.815927,-9.208754,1.000000
+12129,9.845681,-9.235334,1.000000
+12130,9.872261,-9.259534,1.000000
+12131,9.896460,-9.282543,1.000000
+12132,9.924627,-9.308528,1.000000
+12133,9.954976,-9.336893,1.000000
+12134,9.982746,-9.362283,1.000000
+12135,10.007739,-9.385293,1.000000
+12136,10.038881,-9.414055,1.000000
+12137,10.065064,-9.437262,1.000000
+12138,10.097595,-9.464437,1.000000
+12139,10.123977,-9.488042,1.000000
+12140,10.155912,-9.517201,1.000000
+12141,10.180905,-9.539813,1.000000
+12142,10.213039,-9.568377,1.000000
+12143,10.238429,-9.592973,1.000000
+12144,10.270166,-9.622529,1.000000
+12145,10.296548,-9.646728,1.000000
+12146,10.326897,-9.673705,1.000000
+12147,10.356253,-9.700285,1.000000
+12148,10.388784,-9.728650,1.000000
+12149,10.419133,-9.755230,1.000000
+12150,10.449878,-9.783992,1.000000
+12151,10.481020,-9.814935,1.000000
+12152,10.508592,-9.843499,1.000000
+12153,10.536759,-9.875633,1.000000
+12154,10.568099,-9.908560,1.000000
+12155,10.594679,-9.934347,1.000000
+12156,10.624036,-9.961323,1.000000
+12157,10.653195,-9.988300,1.000000
+12158,10.682949,-10.015078,1.000000
+12159,10.716074,-10.045824,1.000000
+12160,10.745828,-10.074189,1.000000
+12161,10.773003,-10.098587,1.000000
+12162,10.804542,-10.127944,1.000000
+12163,10.831518,-10.152342,1.000000
+12164,10.865041,-10.183881,1.000000
+12165,10.893406,-10.211254,1.000000
+12166,10.924945,-10.240413,1.000000
+12167,10.960054,-10.269968,1.000000
+12168,10.989411,-10.294168,1.000000
+12169,11.020950,-10.322334,1.000000
+12170,11.057249,-10.352881,1.000000
+12171,11.086210,-10.379263,1.000000
+12172,11.116162,-10.407231,1.000000
+12173,11.144130,-10.434605,1.000000
+12174,11.176859,-10.466342,1.000000
+12175,11.212564,-10.498873,1.000000
+12176,11.240929,-10.524461,1.000000
+12177,11.271872,-10.553818,1.000000
+12178,11.306387,-10.587737,1.000000
+12179,11.337926,-10.620863,1.000000
+12180,11.364704,-10.651410,1.000000
+12186,11.552945,-10.839849,1.000000
+12187,11.580517,-10.865041,1.000000
+12188,11.612056,-10.895588,1.000000
+12189,11.642603,-10.925738,1.000000
+12190,11.676125,-10.957674,1.000000
+12191,11.707268,-10.987031,1.000000
+12192,11.736823,-11.013214,1.000000
+12193,11.773122,-11.045943,1.000000
+12194,11.802479,-11.072920,1.000000
+12195,11.834415,-11.103268,1.000000
+12196,11.868532,-11.136394,1.000000
+12197,11.900865,-11.167338,1.000000
+12198,11.931808,-11.197488,1.000000
+12199,11.964141,-11.227440,1.000000
+12200,11.997068,-11.256797,1.000000
+12201,12.026623,-11.283576,1.000000
+12202,12.063121,-11.316701,1.000000
+12203,12.092676,-11.344273,1.000000
+12204,12.128778,-11.377200,1.000000
+12205,12.158333,-11.404574,1.000000
+12206,12.193641,-11.437699,1.000000
+12207,12.223394,-11.465668,1.000000
+12208,12.259297,-11.499785,1.000000
+12209,12.292621,-11.532514,1.000000
+12210,12.321581,-11.563458,1.000000
+12211,12.357087,-11.601345,1.000000
+12212,12.389618,-11.637049,1.000000
+12213,12.418776,-11.669580,1.000000
+12214,12.454481,-11.707466,1.000000
+12215,12.482648,-11.737021,1.000000
+12216,12.517757,-11.769155,1.000000
+12217,12.547511,-11.796528,1.000000
+12218,12.584802,-11.830844,1.000000
+12219,12.614754,-11.859209,1.000000
+12220,12.647284,-11.890153,1.000000
+12221,12.679815,-11.920502,1.000000
+12222,12.715520,-11.954818,1.000000
+12223,12.749042,-11.986158,1.000000
+12224,12.781969,-12.017896,1.000000
+12225,12.811723,-12.045071,1.000000
+12226,12.844849,-12.075816,1.000000
+12227,12.878371,-12.106363,1.000000
+12228,12.913084,-12.137902,1.000000
+12229,12.947995,-12.169639,1.000000
+12230,12.982707,-12.200385,1.000000
+12231,13.019602,-12.233510,1.000000
+12232,13.051736,-12.264057,1.000000
+12233,13.086448,-12.296191,1.000000
+12234,13.117590,-12.326143,1.000000
+12235,13.156072,-12.363236,1.000000
+12236,13.186222,-12.393982,1.000000
+12237,13.219745,-12.428496,1.000000
+12238,13.255846,-12.467771,1.000000
+12239,13.285401,-12.499310,1.000000
+12240,13.320907,-12.536998,1.000000
+12241,13.353834,-12.570322,1.000000
+12242,13.387754,-12.601861,1.000000
+12243,13.419689,-12.629234,1.000000
+12244,13.457774,-12.663550,1.000000
+12245,13.492090,-12.695089,1.000000
+12246,13.522438,-12.723652,1.000000
+12247,13.558738,-12.758563,1.000000
+12248,13.591269,-12.790895,1.000000
+12249,13.621419,-12.819261,1.000000
+12250,13.659305,-12.854965,1.000000
+12251,13.691241,-12.883132,1.000000
+12252,13.726350,-12.914076,1.000000
+12253,13.760864,-12.944623,1.000000
+12254,13.798751,-12.979335,-1.000000
+12255,13.829694,-13.008295,-1.000000
+12256,13.866391,-13.044000,-1.000000
+12257,13.894557,-13.069985,-1.000000
+12258,13.918360,-13.087242,-1.000000
+12259,13.925898,-13.091209,-1.000000
+12260,13.924311,-13.085060,-1.000000
+12261,13.919551,-13.075340,-1.000000
+12262,13.915980,-13.064629,-1.000000
+12263,13.913005,-13.050942,-1.000000
\ No newline at end of file
diff --git a/frc971/control_loops/matlab/drivetrain_spin_low.csv b/frc971/control_loops/matlab/drivetrain_spin_low.csv
new file mode 100644
index 0000000..a96acbe
--- /dev/null
+++ b/frc971/control_loops/matlab/drivetrain_spin_low.csv
@@ -0,0 +1,280 @@
+120.220000,16.662837,-14.612612,12.000000,-12.000000
+120.230000,16.662837,-14.612612,12.000000,-12.000000
+120.240000,16.662837,-14.612612,12.000000,-12.000000
+120.250000,16.662837,-14.612612,12.000000,-12.000000
+120.260000,16.662837,-14.612612,12.000000,-12.000000
+120.270000,16.665217,-14.617571,12.000000,-12.000000
+120.280000,16.673152,-14.624117,12.000000,-12.000000
+120.290000,16.682474,-14.632051,12.000000,-12.000000
+120.300000,16.692194,-14.640977,12.000000,-12.000000
+120.310000,16.702112,-14.650895,12.000000,-12.000000
+120.320000,16.713220,-14.660020,12.000000,-12.000000
+120.330000,16.724526,-14.671326,12.000000,-12.000000
+120.340000,16.736626,-14.682632,12.000000,-12.000000
+120.350000,16.748527,-14.693939,12.000000,-12.000000
+120.360000,16.761024,-14.705245,12.000000,-12.000000
+120.370000,16.773719,-14.716552,12.000000,-12.000000
+120.380000,16.786017,-14.728255,12.000000,-12.000000
+120.390000,16.799109,-14.740156,12.000000,-12.000000
+120.400000,16.812002,-14.751661,12.000000,-12.000000
+120.410000,16.824895,-14.763364,12.000000,-12.000000
+120.420000,16.837193,-14.775861,12.000000,-12.000000
+120.430000,16.850087,-14.787960,12.000000,-12.000000
+120.440000,0.0,-0.0,12.000000,-12.000000
+120.450000,0.0,-0.0,12.000000,-12.000000
+120.460000,0.0,-0.0,12.000000,-12.000000
+120.470000,0.0,-0.0,12.000000,-12.000000
+120.480000,16.913759,-14.847864,12.000000,-12.000000
+120.490000,16.926653,-14.860361,12.000000,-12.000000
+120.500000,16.939546,-14.873453,12.000000,-12.000000
+120.510000,16.952439,-14.886147,12.000000,-12.000000
+120.520000,16.965134,-14.899041,12.000000,-12.000000
+120.530000,16.978821,-14.911537,12.000000,-12.000000
+120.540000,16.991714,-14.924232,12.000000,-12.000000
+120.550000,17.004409,-14.936729,12.000000,-12.000000
+120.560000,17.018294,-14.950019,12.000000,-12.000000
+120.570000,17.030592,-14.963110,12.000000,-12.000000
+120.580000,17.043882,-14.976400,12.000000,-12.000000
+120.590000,17.057569,-14.989690,12.000000,-12.000000
+120.600000,17.071850,-15.003178,12.000000,-12.000000
+120.610000,17.085537,-15.016270,12.000000,-12.000000
+120.620000,17.099422,-15.029758,12.000000,-12.000000
+120.630000,17.113109,-15.043048,12.000000,-12.000000
+120.640000,17.127192,-15.056735,12.000000,-12.000000
+120.650000,17.141672,-15.070818,12.000000,-12.000000
+120.660000,17.155756,-15.084505,12.000000,-12.000000
+120.670000,17.170434,-15.098192,12.000000,-12.000000
+120.680000,17.185113,-15.112275,12.000000,-12.000000
+120.690000,17.199990,-15.126359,12.000000,-12.000000
+120.700000,17.214073,-15.140442,12.000000,-12.000000
+120.710000,17.228553,-15.155120,12.000000,-12.000000
+120.720000,17.243430,-15.170196,12.000000,-12.000000
+120.730000,17.258307,-15.184279,12.000000,-12.000000
+120.740000,17.273183,-15.198561,12.000000,-12.000000
+120.750000,17.288259,-15.212842,12.000000,-12.000000
+120.760000,17.303731,-15.227521,12.000000,-12.000000
+120.770000,17.319202,-15.242398,12.000000,-12.000000
+120.780000,17.334674,-15.256878,12.000000,-12.000000
+120.790000,17.350345,-15.272151,12.000000,-12.000000
+120.800000,17.365618,-15.287425,12.000000,-12.000000
+120.810000,17.381288,-15.302500,12.000000,-12.000000
+120.820000,17.396959,-15.317972,12.000000,-12.000000
+120.830000,17.412431,-15.333444,12.000000,-12.000000
+120.840000,17.428101,-15.349313,12.000000,-12.000000
+120.850000,17.443176,-15.364388,12.000000,-12.000000
+120.860000,17.458846,-15.379265,12.000000,-12.000000
+120.870000,17.474318,-15.394340,12.000000,-12.000000
+120.880000,17.489988,-15.409812,12.000000,-12.000000
+120.890000,17.505064,-15.424887,12.000000,-12.000000
+120.900000,17.520932,-15.439962,12.000000,-12.000000
+120.910000,17.536404,-15.455236,12.000000,-12.000000
+120.920000,17.552074,-15.469914,12.000000,-12.000000
+120.930000,17.567745,-15.485188,12.000000,-12.000000
+120.940000,17.584208,-15.501255,12.000000,-12.000000
+120.950000,17.600275,-15.515735,12.000000,-12.000000
+120.960000,17.616541,-15.531207,12.000000,-12.000000
+120.970000,17.633004,-15.546282,12.000000,-12.000000
+120.980000,17.649865,-15.561555,12.000000,-12.000000
+120.990000,17.666527,-15.576234,12.000000,-12.000000
+121.000000,17.682792,-15.591111,12.000000,-12.000000
+121.010000,17.699256,-15.606384,12.000000,-12.000000
+121.020000,17.715521,-15.621658,12.000000,-12.000000
+121.030000,17.731786,-15.636534,12.000000,-12.000000
+121.040000,17.747853,-15.652006,12.000000,-12.000000
+121.050000,17.763722,-15.666883,12.000000,-12.000000
+121.060000,17.779789,-15.682355,12.000000,-12.000000
+121.070000,17.796253,-15.698025,12.000000,-12.000000
+121.080000,17.812716,-15.713696,12.000000,-12.000000
+121.090000,17.828585,-15.728771,12.000000,-12.000000
+121.100000,17.845247,-15.744441,12.000000,-12.000000
+121.110000,17.861512,-15.760310,12.000000,-12.000000
+121.120000,17.877778,-15.775980,12.000000,-12.000000
+121.130000,17.894241,-15.791650,12.000000,-12.000000
+121.140000,17.910507,-15.807519,12.000000,-12.000000
+121.150000,17.926970,-15.822991,12.000000,-12.000000
+121.160000,17.943037,-15.838066,12.000000,-12.000000
+121.170000,17.959104,-15.853736,12.000000,-12.000000
+121.180000,17.975568,-15.869605,12.000000,-12.000000
+121.190000,17.992032,-15.884680,12.000000,-12.000000
+121.200000,18.008694,-15.900747,12.000000,-12.000000
+121.210000,18.024364,-15.916814,12.000000,-12.000000
+121.220000,18.040828,-15.932286,12.000000,-12.000000
+121.230000,18.057291,-15.947559,12.000000,-12.000000
+121.240000,18.073755,-15.963825,12.000000,-12.000000
+121.250000,18.090615,-15.979495,12.000000,-12.000000
+121.260000,18.107476,-15.995959,12.000000,-12.000000
+121.270000,18.123939,-16.011232,12.000000,-12.000000
+121.280000,18.140998,-16.027299,12.000000,-12.000000
+121.290000,18.157462,-16.042573,12.000000,-12.000000
+121.300000,18.174719,-16.058838,12.000000,-12.000000
+121.310000,18.191183,-16.074707,12.000000,-12.000000
+121.320000,18.208242,-16.090575,12.000000,-12.000000
+121.330000,18.225102,-16.106444,12.000000,-12.000000
+121.340000,18.242161,-16.122511,12.000000,-12.000000
+121.350000,18.258823,-16.138181,12.000000,-12.000000
+121.360000,18.276080,-16.154248,12.000000,-12.000000
+121.370000,18.292742,-16.169918,12.000000,-12.000000
+121.380000,18.309801,-16.185588,12.000000,-12.000000
+121.390000,18.326463,-16.201655,12.000000,-12.000000
+121.400000,18.343521,-16.217524,12.000000,-12.000000
+121.410000,18.359985,-16.232996,12.000000,-12.000000
+121.420000,18.377242,-16.249063,12.000000,-12.000000
+121.430000,18.394301,-16.265130,12.000000,-12.000000
+121.440000,18.411558,-16.280800,12.000000,-12.000000
+121.450000,0.0,-0.0,12.000000,-12.000000
+121.460000,0.0,-0.0,12.000000,-12.000000
+121.470000,0.0,-0.0,12.000000,-12.000000
+121.480000,18.480587,-16.345068,12.000000,-12.000000
+121.490000,18.497447,-16.360738,12.000000,-12.000000
+121.500000,18.514506,-16.377202,12.000000,-12.000000
+121.510000,18.531564,-16.392475,12.000000,-12.000000
+121.520000,18.548623,-16.408542,12.000000,-12.000000
+121.530000,18.565880,-16.424609,12.000000,-12.000000
+121.540000,18.582542,-16.441073,12.000000,-12.000000
+121.550000,18.599601,-16.456743,12.000000,-12.000000
+121.560000,18.616858,-16.473009,12.000000,-12.000000
+121.570000,18.633520,-16.489274,12.000000,-12.000000
+121.580000,18.650381,-16.505738,12.000000,-12.000000
+121.590000,18.666646,-16.522003,12.000000,-12.000000
+121.600000,18.683705,-16.537673,12.000000,-12.000000
+121.610000,18.700764,-16.553542,12.000000,-12.000000
+121.620000,18.718219,-16.570204,12.000000,-12.000000
+121.630000,18.734683,-16.585676,12.000000,-12.000000
+121.640000,18.752138,-16.602140,12.000000,-12.000000
+121.650000,18.768602,-16.618008,12.000000,-12.000000
+121.660000,18.785661,-16.634075,12.000000,-12.000000
+121.670000,18.802521,-16.649745,12.000000,-12.000000
+121.680000,18.819977,-16.666011,12.000000,-12.000000
+121.690000,18.836440,-16.681879,12.000000,-12.000000
+121.700000,18.853301,-16.697748,12.000000,-12.000000
+121.710000,18.870161,-16.713617,12.000000,-12.000000
+121.720000,18.887815,-16.729882,12.000000,-12.000000
+121.730000,18.904675,-16.745949,12.000000,-12.000000
+121.740000,18.921932,-16.762214,12.000000,-12.000000
+121.750000,18.938594,-16.777686,12.000000,-12.000000
+121.760000,18.955653,-16.793555,12.000000,-12.000000
+121.770000,18.972910,-16.809423,12.000000,-12.000000
+121.780000,18.990564,-16.825689,12.000000,-12.000000
+121.790000,19.007623,-16.841359,12.000000,-12.000000
+121.800000,19.025078,-16.857426,12.000000,-12.000000
+121.810000,19.041740,-16.873096,12.000000,-12.000000
+121.820000,19.058998,-16.889163,12.000000,-12.000000
+121.830000,19.076056,-16.905032,12.000000,-12.000000
+121.840000,19.094107,-16.921694,12.000000,-12.000000
+121.850000,19.110372,-16.937364,12.000000,-12.000000
+121.860000,19.128423,-16.953828,12.000000,-12.000000
+121.870000,19.144886,-16.969300,12.000000,-12.000000
+121.880000,19.162540,-16.986160,12.000000,-12.000000
+121.890000,19.179004,-17.001433,12.000000,-12.000000
+121.900000,19.196459,-17.017897,12.000000,-12.000000
+121.910000,19.213716,-17.033964,12.000000,-12.000000
+121.920000,19.231172,-17.050428,12.000000,-12.000000
+121.930000,19.248231,-17.066098,12.000000,-12.000000
+121.940000,19.265885,-17.082562,12.000000,-12.000000
+121.950000,19.283340,-17.099025,12.000000,-12.000000
+121.960000,19.301192,-17.115886,12.000000,-12.000000
+121.970000,19.318251,-17.131754,12.000000,-12.000000
+121.980000,19.335905,-17.148218,12.000000,-12.000000
+121.990000,19.352765,-17.164285,12.000000,-12.000000
+122.000000,19.370022,-17.180947,12.000000,-12.000000
+122.010000,19.387081,-17.197411,12.000000,-12.000000
+122.020000,19.404933,-17.214073,12.000000,-12.000000
+122.030000,19.421199,-17.229942,12.000000,-12.000000
+122.040000,19.439448,-17.247000,12.000000,-12.000000
+122.050000,19.455514,-17.262472,12.000000,-12.000000
+122.060000,19.472772,-17.279333,12.000000,-12.000000
+122.070000,19.489632,-17.295400,12.000000,-12.000000
+122.080000,19.507087,-17.311665,12.000000,-12.000000
+122.090000,19.523948,-17.327930,12.000000,-12.000000
+122.100000,19.541403,-17.343799,12.000000,-12.000000
+122.110000,19.558462,-17.360064,12.000000,-12.000000
+122.120000,19.576116,-17.376925,12.000000,-12.000000
+122.130000,19.592976,-17.392992,12.000000,-12.000000
+122.140000,19.610432,-17.409654,12.000000,-12.000000
+122.150000,19.627491,-17.425125,12.000000,-12.000000
+122.160000,19.644946,-17.441788,12.000000,-12.000000
+122.170000,19.661608,-17.457458,12.000000,-12.000000
+122.180000,19.679262,-17.473525,12.000000,-12.000000
+122.190000,19.696321,-17.489195,12.000000,-12.000000
+122.200000,19.713379,-17.505262,12.000000,-12.000000
+122.210000,19.730438,-17.520932,12.000000,-12.000000
+122.220000,19.748687,-17.537198,12.000000,-12.000000
+122.230000,19.765349,-17.552868,12.000000,-12.000000
+122.240000,19.783003,-17.569728,12.000000,-12.000000
+122.250000,19.799665,-17.585398,12.000000,-12.000000
+122.260000,19.817517,-17.601862,12.000000,-12.000000
+122.270000,19.834378,-17.617136,12.000000,-12.000000
+122.280000,19.851635,-17.633401,12.000000,-12.000000
+122.290000,19.869090,-17.649270,12.000000,-12.000000
+122.300000,19.886347,-17.665535,12.000000,-12.000000
+122.310000,19.903604,-17.681404,12.000000,-12.000000
+122.320000,19.921258,-17.698066,12.000000,-12.000000
+122.330000,19.938119,-17.713934,12.000000,-12.000000
+122.340000,19.955177,-17.729803,12.000000,-12.000000
+122.350000,19.972435,-17.746068,12.000000,-12.000000
+122.360000,19.989692,-17.762532,12.000000,-12.000000
+122.370000,20.005957,-17.778400,12.000000,-12.000000
+122.380000,20.023611,-17.794864,12.000000,-12.000000
+122.390000,20.040075,-17.810534,12.000000,-12.000000
+122.400000,20.057530,-17.826998,12.000000,-12.000000
+122.410000,20.074589,-17.842867,12.000000,-12.000000
+122.420000,20.092243,-17.859925,12.000000,-12.000000
+122.430000,20.109103,-17.875199,12.000000,-12.000000
+122.440000,20.126360,-17.891663,12.000000,-12.000000
+122.450000,0.0,-0.0,12.000000,-12.000000
+122.460000,0.0,-0.0,12.000000,-12.000000
+122.470000,0.0,-0.0,12.000000,-12.000000
+122.480000,20.195587,-17.957319,12.000000,-12.000000
+122.490000,20.212249,-17.973188,12.000000,-12.000000
+122.500000,20.229506,-17.989651,12.000000,-12.000000
+122.510000,20.246565,-18.005520,12.000000,-12.000000
+122.520000,20.263822,-18.022182,12.000000,-12.000000
+122.530000,20.281079,-18.038051,12.000000,-12.000000
+122.540000,20.298733,-18.054911,12.000000,-12.000000
+122.550000,20.314998,-18.070185,12.000000,-12.000000
+122.560000,20.333049,-18.087243,12.000000,-12.000000
+122.570000,20.350108,-18.102914,12.000000,-12.000000
+122.580000,20.367761,-18.119576,12.000000,-12.000000
+122.590000,20.385018,-18.135643,12.000000,-12.000000
+122.600000,20.402276,-18.152106,12.000000,-12.000000
+122.610000,20.419929,-18.167777,12.000000,-12.000000
+122.620000,20.437782,-18.184835,12.000000,-12.000000
+122.630000,20.455039,-18.200704,12.000000,-12.000000
+122.640000,20.472296,-18.216969,12.000000,-12.000000
+122.650000,20.489355,-18.233036,12.000000,-12.000000
+122.660000,20.507604,-18.249698,12.000000,-12.000000
+122.670000,20.524861,-18.265170,12.000000,-12.000000
+122.680000,20.542118,-18.281634,12.000000,-12.000000
+122.690000,20.559177,-18.297106,12.000000,-12.000000
+122.700000,20.576235,-18.313371,12.000000,-12.000000
+122.710000,20.593492,-18.329240,12.000000,-12.000000
+122.720000,20.610948,-18.346100,12.000000,-12.000000
+122.730000,20.628205,-18.361770,12.000000,-12.000000
+122.740000,20.646454,-18.378631,12.000000,-12.000000
+122.750000,20.662918,-18.393904,12.000000,-12.000000
+122.760000,20.681166,-18.410765,12.000000,-12.000000
+122.770000,20.697829,-18.426435,12.000000,-12.000000
+122.780000,20.715681,-18.442700,12.000000,-12.000000
+122.790000,20.732739,-18.458767,12.000000,-12.000000
+122.800000,20.749997,-18.474636,12.000000,-12.000000
+122.810000,20.767254,-18.491100,12.000000,-12.000000
+122.820000,20.784709,-18.507762,12.000000,-12.000000
+122.830000,20.802958,-18.525217,12.000000,-12.000000
+122.840000,20.820017,-18.541681,12.000000,-12.000000
+122.850000,20.835290,-18.555962,12.000000,-12.000000
+122.860000,20.852547,-18.572228,12.000000,-12.000000
+122.870000,0.0,-0.0,12.000000,-12.000000
+122.880000,0.0,-0.0,12.000000,-12.000000
+122.890000,0.0,-0.0,12.000000,-12.000000
+122.900000,0.0,-0.0,12.000000,-12.000000
+122.910000,20.938833,-18.652959,12.000000,-12.000000
+122.920000,20.956289,-18.669026,12.000000,-12.000000
+122.930000,20.973744,-18.685292,12.000000,-12.000000
+122.940000,20.991596,-18.702350,12.000000,-12.000000
+122.950000,21.008258,-18.718021,12.000000,-12.000000
+122.960000,21.025912,-18.734683,12.000000,-12.000000
+122.970000,21.042772,-18.750948,12.000000,-12.000000
+122.980000,21.061021,-18.768205,12.000000,-12.000000
+122.990000,21.077882,-18.783875,12.000000,-12.000000
+123.000000,21.094941,-18.800141,12.000000,-12.000000
+123.010000,21.111999,-18.816406,12.000000,-12.000000
diff --git a/frc971/control_loops/matlab/drivetrain_spin_low.mat b/frc971/control_loops/matlab/drivetrain_spin_low.mat
new file mode 100644
index 0000000..457083f
--- /dev/null
+++ b/frc971/control_loops/matlab/drivetrain_spin_low.mat
Binary files differ
diff --git a/frc971/control_loops/matlab/drivetrain_strait_low.csv b/frc971/control_loops/matlab/drivetrain_strait_low.csv
new file mode 100644
index 0000000..6966f5b
--- /dev/null
+++ b/frc971/control_loops/matlab/drivetrain_strait_low.csv
@@ -0,0 +1,103 @@
+11.590000,15.318369,-16.398228,12.000000,12.000000
+11.600000,15.318369,-16.398228,12.000000,12.000000
+11.610000,15.318369,-16.398228,12.000000,12.000000
+11.620000,15.318369,-16.398228,12.000000,12.000000
+11.630000,15.318369,-16.398228,12.000000,12.000000
+11.640000,15.321146,-16.395649,12.000000,12.000000
+11.650000,15.329278,-16.388707,12.000000,12.000000
+11.660000,15.338403,-16.380772,12.000000,12.000000
+11.670000,15.347924,-16.372045,12.000000,12.000000
+11.680000,15.358635,-16.362325,12.000000,12.000000
+11.690000,15.369545,-16.351812,12.000000,12.000000
+11.700000,15.381050,-16.341101,12.000000,12.000000
+11.710000,15.392555,-16.329993,12.000000,12.000000
+11.720000,15.404258,-16.319083,12.000000,12.000000
+11.730000,15.415961,-16.308173,12.000000,12.000000
+11.740000,15.428061,-16.294685,12.000000,12.000000
+11.750000,15.440954,-16.283379,12.000000,12.000000
+11.760000,15.453847,-16.268502,12.000000,12.000000
+11.770000,15.466939,-16.255014,12.000000,12.000000
+11.780000,15.479038,-16.241327,12.000000,12.000000
+11.790000,15.491138,-16.228235,12.000000,12.000000
+11.800000,15.503635,-16.216136,12.000000,12.000000
+11.810000,15.515933,-16.204234,12.000000,12.000000
+11.820000,15.528628,-16.192134,12.000000,12.000000
+11.830000,15.541521,-16.179043,12.000000,12.000000
+11.840000,15.554811,-16.165951,12.000000,12.000000
+11.850000,15.568299,-16.152859,12.000000,12.000000
+11.860000,15.581589,-16.139569,12.000000,12.000000
+11.870000,15.595673,-16.126081,12.000000,12.000000
+11.880000,15.610153,-16.112791,12.000000,12.000000
+11.890000,15.624435,-16.098708,12.000000,12.000000
+11.900000,15.638716,-16.084228,12.000000,12.000000
+11.910000,15.653395,-16.069946,12.000000,12.000000
+11.920000,15.668272,-16.055466,12.000000,12.000000
+11.930000,15.683347,-16.040787,12.000000,12.000000
+11.940000,15.698620,-16.026307,12.000000,12.000000
+11.950000,15.714092,-16.011430,12.000000,12.000000
+11.960000,15.728969,-15.996554,12.000000,12.000000
+11.970000,15.744243,-15.981478,12.000000,12.000000
+11.980000,15.759715,-15.966205,12.000000,12.000000
+11.990000,15.774988,-15.950931,12.000000,12.000000
+12.000000,15.789865,-15.935459,12.000000,12.000000
+12.010000,15.805535,-15.920186,12.000000,12.000000
+12.020000,15.821205,-15.904516,12.000000,12.000000
+12.030000,15.836876,-15.888845,12.000000,12.000000
+12.040000,15.852744,-15.873175,12.000000,12.000000
+12.050000,15.868613,-15.857703,12.000000,12.000000
+12.060000,15.884680,-15.841835,12.000000,12.000000
+12.070000,15.900747,-15.826164,12.000000,12.000000
+12.080000,15.916615,-15.810296,12.000000,12.000000
+12.090000,15.932881,-15.794427,12.000000,12.000000
+12.100000,15.949146,-15.778162,12.000000,12.000000
+12.110000,15.965213,-15.762293,12.000000,12.000000
+12.120000,15.981677,-15.746226,12.000000,12.000000
+12.130000,0.0,-0.0,12.000000,12.000000
+12.140000,0.0,-0.0,12.000000,12.000000
+12.150000,0.0,-0.0,12.000000,12.000000
+12.160000,16.048127,-15.680173,12.000000,12.000000
+12.170000,16.064194,-15.663709,12.000000,12.000000
+12.180000,16.081649,-15.647047,12.000000,12.000000
+12.190000,16.098113,-15.630385,12.000000,12.000000
+12.200000,16.114973,-15.613525,12.000000,12.000000
+12.210000,16.131834,-15.597061,12.000000,12.000000
+12.220000,16.148892,-15.580399,12.000000,12.000000
+12.230000,16.165951,-15.563340,12.000000,12.000000
+12.240000,16.183010,-15.546877,12.000000,12.000000
+12.250000,16.200069,-15.530016,12.000000,12.000000
+12.260000,16.217326,-15.512958,12.000000,12.000000
+12.270000,16.234583,-15.495700,12.000000,12.000000
+12.280000,16.251840,-15.478840,12.000000,12.000000
+12.290000,16.268899,-15.461980,12.000000,12.000000
+12.300000,16.286156,-15.445119,12.000000,12.000000
+12.310000,16.303215,-15.428061,12.000000,12.000000
+12.320000,16.320273,-15.411002,12.000000,12.000000
+12.330000,16.337729,-15.393943,12.000000,12.000000
+12.340000,16.354589,-15.376884,12.000000,12.000000
+12.350000,16.371648,-15.359825,12.000000,12.000000
+12.360000,16.389103,-15.342767,12.000000,12.000000
+12.370000,16.406162,-15.325708,12.000000,12.000000
+12.380000,16.423221,-15.308649,12.000000,12.000000
+12.390000,16.440676,-15.291590,12.000000,12.000000
+12.400000,16.457934,-15.274333,12.000000,12.000000
+12.410000,16.475191,-15.257671,12.000000,12.000000
+12.420000,16.492646,-15.240216,12.000000,12.000000
+12.430000,16.509903,-15.222959,12.000000,12.000000
+12.440000,16.527557,-15.205900,12.000000,12.000000
+12.450000,16.544616,-15.189040,12.000000,12.000000
+12.460000,16.561873,-15.171782,12.000000,12.000000
+12.470000,16.579130,-15.154922,12.000000,12.000000
+12.480000,16.596982,-15.137665,12.000000,12.000000
+12.490000,16.614239,-15.120209,12.000000,12.000000
+12.500000,16.631100,-15.103151,12.000000,12.000000
+12.510000,16.648159,-15.085894,12.000000,12.000000
+12.520000,16.666011,-15.068636,12.000000,12.000000
+12.530000,16.683069,-15.051379,12.000000,12.000000
+12.540000,16.700327,-15.034321,12.000000,12.000000
+12.550000,16.717782,-15.017262,12.000000,12.000000
+12.560000,16.734841,-15.000203,12.000000,12.000000
+12.570000,16.752495,-14.982946,12.000000,12.000000
+12.580000,16.769752,-14.965887,12.000000,12.000000
+12.590000,16.787009,-14.948828,12.000000,12.000000
+12.600000,16.804464,-14.931175,12.000000,12.000000
+12.610000,16.821920,-14.914314,12.000000,12.000000
diff --git a/frc971/control_loops/matlab/drivetrain_strait_low.mat b/frc971/control_loops/matlab/drivetrain_strait_low.mat
new file mode 100644
index 0000000..e6a4973
--- /dev/null
+++ b/frc971/control_loops/matlab/drivetrain_strait_low.mat
Binary files differ
diff --git a/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.csv b/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.csv
new file mode 100644
index 0000000..0091dd2
--- /dev/null
+++ b/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.csv
@@ -0,0 +1,185 @@
+31783,-2.373349,-1.651328,1.000000
+31784,-2.373349,-1.651328,1.000000
+31785,-2.373349,-1.651328,1.000000
+31786,-2.373349,-1.651328,1.000000
+31787,-2.370771,-1.651328,1.000000
+31788,-2.364622,-1.649344,1.000000
+31789,-2.356489,-1.639624,1.000000
+31790,-2.348158,-1.632880,1.000000
+31791,-2.336257,-1.622367,1.000000
+31792,-2.325744,-1.612449,1.000000
+31793,-2.312652,-1.599755,1.000000
+31794,-2.301941,-1.589440,1.000000
+31795,-2.288651,-1.577142,1.000000
+31796,-2.278138,-1.567224,1.000000
+31797,-2.263856,-1.553934,1.000000
+31798,-2.251558,-1.542231,1.000000
+31799,-2.236681,-1.526957,1.000000
+31800,-2.223589,-1.513072,1.000000
+31801,-2.211093,-1.499386,1.000000
+31802,-2.198200,-1.486294,1.000000
+31803,-2.185505,-1.473004,1.000000
+31804,-2.173603,-1.462491,1.000000
+31805,-2.160115,-1.450193,1.000000
+31806,-2.145238,-1.436506,1.000000
+31807,-2.131353,-1.423613,1.000000
+31808,-2.117666,-1.410521,1.000000
+31809,-2.103980,-1.397231,1.000000
+31810,-2.089500,-1.383148,1.000000
+31811,-2.076011,-1.369660,1.000000
+31812,-2.063316,-1.357163,1.000000
+31813,-2.047646,-1.341493,1.000000
+31814,-2.034356,-1.328600,1.000000
+31815,-2.017496,-1.312533,1.000000
+31816,-2.002619,-1.297854,1.000000
+31817,-1.987544,-1.282977,1.000000
+31818,-1.974055,-1.269886,1.000000
+31819,-1.957195,-1.253819,1.000000
+31820,-1.941525,-1.238347,1.000000
+31821,-1.927441,-1.224859,1.000000
+31822,-1.910383,-1.208197,1.000000
+31823,-1.896299,-1.194311,1.000000
+31824,-1.879042,-1.177253,1.000000
+31825,-1.862578,-1.161384,1.000000
+31826,-1.846908,-1.145515,1.000000
+31827,-1.829254,-1.128060,1.000000
+31828,-1.814378,-1.114175,1.000000
+31829,-1.798906,-1.098306,1.000000
+31830,-1.782442,-1.081644,1.000000
+31831,-1.765978,-1.065776,1.000000
+31832,-1.751697,-1.051097,1.000000
+31833,-1.735233,-1.035229,1.000000
+31834,-1.718571,-1.019162,1.000000
+31835,-1.700124,-1.000913,1.000000
+31836,-1.683461,-0.984846,1.000000
+31837,-1.666799,-0.968382,1.000000
+31838,-1.650137,-0.952117,1.000000
+31839,-1.633277,-0.935851,1.000000
+31840,-1.616020,-0.919189,1.000000
+31841,-1.599358,-0.902527,1.000000
+31842,-1.582696,-0.885469,1.000000
+31843,-1.565835,-0.868608,1.000000
+31844,-1.548975,-0.851748,1.000000
+31845,-1.533305,-0.836474,1.000000
+31846,-1.516643,-0.820209,1.000000
+31847,-1.497997,-0.801762,1.000000
+31848,-1.481137,-0.784901,1.000000
+31849,-1.463880,-0.767843,1.000000
+31850,-1.446424,-0.750784,1.000000
+31851,-1.430952,-0.735709,1.000000
+31852,-1.411711,-0.717261,1.000000
+31853,-1.396240,-0.701789,1.000000
+31854,-1.377197,-0.682747,1.000000
+31855,-1.359543,-0.665688,1.000000
+31856,-1.342286,-0.648630,1.000000
+31857,-1.325029,-0.631174,1.000000
+31864,-1.204626,-0.512358,1.000000
+31865,-1.187171,-0.495299,1.000000
+31866,-1.169517,-0.478240,1.000000
+31867,-1.152260,-0.460785,1.000000
+31868,-1.134606,-0.443726,1.000000
+31869,-1.117150,-0.426667,1.000000
+31870,-1.097116,-0.407228,1.000000
+31871,-1.081446,-0.391756,1.000000
+31872,-1.062205,-0.373111,1.000000
+31873,-1.044551,-0.355457,1.000000
+31874,-1.027096,-0.337803,1.000000
+31875,-1.009045,-0.320546,1.000000
+31876,-0.993574,-0.304876,1.000000
+31877,-0.974134,-0.286032,1.000000
+31878,-0.958861,-0.270560,1.000000
+31879,-0.939422,-0.250724,1.000000
+31880,-0.921371,-0.233467,1.000000
+31881,-0.903916,-0.216408,1.000000
+31882,-0.886659,-0.199349,1.000000
+31883,-0.870592,-0.183679,1.000000
+31884,-0.850954,-0.164439,1.000000
+31885,-0.834887,-0.148768,1.000000
+31886,-0.815448,-0.129726,1.000000
+31887,-0.797795,-0.112667,1.000000
+31888,-0.779942,-0.095013,1.000000
+31889,-0.762090,-0.077955,1.000000
+31890,-0.746420,-0.061689,1.000000
+31891,-0.727179,-0.042647,1.000000
+31892,-0.709525,-0.025390,1.000000
+31893,-0.693657,-0.009720,1.000000
+31894,-0.674416,0.009323,1.000000
+31895,-0.658349,0.025390,1.000000
+31896,-0.640695,0.042449,1.000000
+31897,-0.621455,0.061491,1.000000
+31898,-0.603999,0.078748,1.000000
+31899,-0.586147,0.096402,1.000000
+31900,-0.567898,0.113659,1.000000
+31901,-0.550443,0.130718,1.000000
+31902,-0.532590,0.148570,1.000000
+31903,-0.514936,0.165827,1.000000
+31904,-0.497283,0.183282,1.000000
+31905,-0.481216,0.199151,1.000000
+31906,-0.463562,0.216607,1.000000
+31907,-0.445710,0.234062,1.000000
+31908,-0.428056,0.251518,1.000000
+31909,-0.408815,0.270560,1.000000
+31910,-0.390765,0.288412,1.000000
+31911,-0.373706,0.305471,1.000000
+31912,-0.357441,0.320943,1.000000
+31913,-0.337803,0.340580,1.000000
+31914,-0.321934,0.356052,1.000000
+31915,-0.302495,0.375491,1.000000
+31916,-0.284643,0.392550,1.000000
+31917,-0.266791,0.410005,1.000000
+31918,-0.248939,0.427659,1.000000
+31919,-0.231285,0.444916,1.000000
+31920,-0.213234,0.462570,1.000000
+31921,-0.195581,0.479827,1.000000
+31922,-0.178125,0.497084,1.000000
+31923,-0.160273,0.514738,1.000000
+31924,-0.142818,0.532194,1.000000
+31925,-0.126949,0.548261,1.000000
+31926,-0.109097,0.566113,1.000000
+31927,-0.089459,0.585552,1.000000
+31928,-0.071607,0.602809,1.000000
+31929,-0.053557,0.620463,1.000000
+31930,-0.035308,0.638315,1.000000
+31931,-0.017852,0.655572,1.000000
+31932,0.000198,0.673424,1.000000
+31933,0.016265,0.688896,1.000000
+31934,0.036101,0.708732,1.000000
+31935,0.054152,0.726187,1.000000
+31936,0.071607,0.743841,1.000000
+31937,0.089658,0.761693,1.000000
+31938,0.107113,0.779149,1.000000
+31939,0.124965,0.796803,1.000000
+31940,0.141429,0.812671,1.000000
+31941,0.158884,0.830325,1.000000
+31942,0.177927,0.849368,1.000000
+31943,0.195581,0.867418,1.000000
+31944,0.213433,0.884874,1.000000
+31945,0.229500,0.900742,1.000000
+31946,0.249336,0.919784,1.000000
+31947,0.266989,0.937240,1.000000
+31948,0.285040,0.954695,1.000000
+31949,0.301107,0.970564,1.000000
+31950,0.320943,0.989805,1.000000
+31951,0.338200,1.007260,1.000000
+31952,0.355854,1.024517,1.000000
+31953,0.372119,1.040584,1.000000
+31954,0.391360,1.059627,1.000000
+31955,0.409609,1.077479,1.000000
+31956,0.426866,1.094934,1.000000
+31957,0.444718,1.112191,1.000000
+31964,0.566906,1.232793,1.000000
+31965,0.584362,1.250248,-1.000000
+31966,0.602412,1.267902,-1.000000
+31967,0.620066,1.285556,-1.000000
+31968,0.637720,1.302615,-1.000000
+31969,0.656762,1.317690,-1.000000
+31970,0.664895,1.321062,-1.000000
+31971,0.667077,1.320070,-1.000000
+31972,0.669655,1.316698,-1.000000
+31973,0.666482,1.313524,-1.000000
+31974,0.660928,1.307177,-1.000000
+31975,0.652002,1.297656,-1.000000
+31976,0.641687,1.287143,-1.000000
+31977,0.630777,1.276630,-1.000000
+31978,0.619273,1.268101,-1.000000
+31979,0.608760,1.256992,-1.000000
\ No newline at end of file
diff --git a/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.mat b/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.mat
new file mode 100644
index 0000000..e9cd690
--- /dev/null
+++ b/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.mat
Binary files differ
diff --git a/frc971/control_loops/matlab/writeMat.m b/frc971/control_loops/matlab/writeMat.m
new file mode 100644
index 0000000..b1541f5
--- /dev/null
+++ b/frc971/control_loops/matlab/writeMat.m
@@ -0,0 +1,16 @@
+function writeMat(fd, matrix, name)
+ %fprintf(fd, '%s = init_matrix(%d, %d);\n', name, size(matrix, 1), size(matrix, 2));
+ fprintf(fd, '%s << ', name);
+ first_loop = 1;
+ for i=1:size(matrix, 1)
+ for j=1:size(matrix, 2)
+ if first_loop
+ first_loop = 0;
+ else
+ fprintf(fd, ', ');
+ end
+ fprintf(fd, '%.10f', matrix(i, j));
+ end
+ end
+ fprintf(fd, '; \\\n');
+end
\ No newline at end of file
diff --git a/frc971/control_loops/matlab/writeMatFlash.m b/frc971/control_loops/matlab/writeMatFlash.m
new file mode 100644
index 0000000..10104d0
--- /dev/null
+++ b/frc971/control_loops/matlab/writeMatFlash.m
@@ -0,0 +1,16 @@
+function writeMatFlash(fd, matrix, name)
+ %fprintf(fd, '%s = init_matrix(%d, %d);\n', name, size(matrix, 1), size(matrix, 2));
+ fprintf(fd, 'flash_matrix(%s, ', name);
+ first_loop = 1;
+ for i=1:size(matrix, 1)
+ for j=1:size(matrix, 2)
+ if first_loop
+ first_loop = 0;
+ else
+ fprintf(fd, ', ');
+ end
+ fprintf(fd, '%.10f', matrix(i, j));
+ end
+ end
+ fprintf(fd, ');\n');
+end
diff --git a/frc971/control_loops/matlab/writeMatFooter.m b/frc971/control_loops/matlab/writeMatFooter.m
new file mode 100644
index 0000000..b23664e
--- /dev/null
+++ b/frc971/control_loops/matlab/writeMatFooter.m
@@ -0,0 +1,3 @@
+function writeMatFooter(fd)
+ fprintf(fd, '\n');
+end
\ No newline at end of file
diff --git a/frc971/control_loops/matlab/writeMatFooterFlash.m b/frc971/control_loops/matlab/writeMatFooterFlash.m
new file mode 100644
index 0000000..5326a94
--- /dev/null
+++ b/frc971/control_loops/matlab/writeMatFooterFlash.m
@@ -0,0 +1,3 @@
+function writeMatFooterFlash(fd)
+ fprintf(fd, '\n');
+end
diff --git a/frc971/control_loops/matlab/writeMatHeader.m b/frc971/control_loops/matlab/writeMatHeader.m
new file mode 100644
index 0000000..5c100f3
--- /dev/null
+++ b/frc971/control_loops/matlab/writeMatHeader.m
@@ -0,0 +1,4 @@
+function writeMatHeader(fd, number_of_states, number_of_outputs)
+ fprintf(fd, 'typedef StateFeedbackLoop<%d, %d> MatrixClass;\n', number_of_states, number_of_outputs);
+ fprintf(fd, '#define MATRIX_INIT ');
+end
\ No newline at end of file
diff --git a/frc971/control_loops/matlab/writeMatHeaderFlash.m b/frc971/control_loops/matlab/writeMatHeaderFlash.m
new file mode 100644
index 0000000..88a6cc6
--- /dev/null
+++ b/frc971/control_loops/matlab/writeMatHeaderFlash.m
@@ -0,0 +1,4 @@
+function writeMatHeaderFlash(fd, number_of_states, number_of_outputs)
+ fprintf(fd, 'typedef StateFeedbackLoop<%d, %d> MatrixClass;\n', number_of_states, number_of_outputs);
+ fprintf(fd, '#define MATRIX_INIT ');
+end
diff --git a/frc971/control_loops/python/controls.py b/frc971/control_loops/python/controls.py
new file mode 100644
index 0000000..7d34a85
--- /dev/null
+++ b/frc971/control_loops/python/controls.py
@@ -0,0 +1,83 @@
+#!/usr/bin/python
+
+"""
+Control loop pole placement library.
+
+This library will grow to support many different pole placement methods.
+Currently it only supports direct pole placement.
+"""
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+import numpy
+import slycot
+
+class Error (Exception):
+ """Base class for all control loop exceptions."""
+
+
+class PolePlacementError(Error):
+ """Exception raised when pole placement fails."""
+
+
+# TODO(aschuh): dplace should take a control system object.
+# There should also exist a function to manipulate laplace expressions, and
+# something to plot bode plots and all that.
+def dplace(A, B, poles, alpha=1e-6):
+ """Set the poles of (A - BF) to poles.
+
+ Args:
+ A: numpy.matrix(n x n), The A matrix.
+ B: numpy.matrix(n x m), The B matrix.
+ poles: array(imaginary numbers), The poles to use. Complex conjugates poles
+ must be in pairs.
+
+ Raises:
+ ValueError: Arguments were the wrong shape or there were too many poles.
+ PolePlacementError: Pole placement failed.
+
+ Returns:
+ numpy.matrix(m x n), K
+ """
+ # See http://www.icm.tu-bs.de/NICONET/doc/SB01BD.html for a description of the
+ # fortran code that this is cleaning up the interface to.
+ n = A.shape[0]
+ if A.shape[1] != n:
+ raise ValueError("A must be square")
+ if B.shape[0] != n:
+ raise ValueError("B must have the same number of states as A.")
+ m = B.shape[1]
+
+ num_poles = len(poles)
+ if num_poles > n:
+ raise ValueError("Trying to place more poles than states.")
+
+ out = slycot.sb01bd(n=n,
+ m=m,
+ np=num_poles,
+ alpha=alpha,
+ A=A,
+ B=B,
+ w=numpy.array(poles),
+ dico='D')
+
+ A_z = numpy.matrix(out[0])
+ num_too_small_eigenvalues = out[2]
+ num_assigned_eigenvalues = out[3]
+ num_uncontrollable_eigenvalues = out[4]
+ K = numpy.matrix(-out[5])
+ Z = numpy.matrix(out[6])
+
+ if num_too_small_eigenvalues != 0:
+ raise PolePlacementError("Number of eigenvalues that are too small "
+ "and are therefore unmodified is %d." %
+ num_too_small_eigenvalues)
+ if num_assigned_eigenvalues != num_poles:
+ raise PolePlacementError("Did not place all the eigenvalues that were "
+ "requested. Only placed %d eigenvalues." %
+ num_assigned_eigenvalues)
+ if num_uncontrollable_eigenvalues != 0:
+ raise PolePlacementError("Found %d uncontrollable eigenvlaues." %
+ num_uncontrollable_eigenvalues)
+
+ return K
diff --git a/frc971/control_loops/python/libcdd.py b/frc971/control_loops/python/libcdd.py
new file mode 100644
index 0000000..a217728
--- /dev/null
+++ b/frc971/control_loops/python/libcdd.py
@@ -0,0 +1,129 @@
+#!/usr/bin/python
+
+"""Wrapper around libcdd, a polytope manipulation library."""
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+import ctypes
+
+# Wrapper around PyFile_AsFile so that we can print out the error messages.
+# Set the arg type and return types of the function call.
+class FILE(ctypes.Structure):
+ pass
+
+ctypes.pythonapi.PyFile_AsFile.argtypes = [ctypes.py_object]
+ctypes.pythonapi.PyFile_AsFile.restype = ctypes.POINTER(FILE)
+
+# Load and init libcdd. libcdd is a C library that implements algorithm to
+# manipulate half space and vertex representations of polytopes.
+# Unfortunately, the library was compiled with C++ even though it has a lot of C
+# code in it, so all the symbol names are mangled. Ug.
+libcdd = ctypes.cdll.LoadLibrary('libcdd.so')
+libcdd._Z23dd_set_global_constantsv()
+
+# The variable type mytype that libcdd defines (double[1])
+# See http://docs.python.org/2/library/ctypes.html#arrays for the documentation
+# explaining why ctypes.c_double * 1 => double[1]
+# libcdd defines mytype to various things so it can essentially template its
+# functions. What a weird library.
+mytype = ctypes.c_double * 1
+
+
+# Forward declaration for the polyhedra data structure.
+class dd_polyhedradata(ctypes.Structure):
+ pass
+
+
+# Definition of dd_matrixdata
+class dd_matrixdata(ctypes.Structure):
+ _fields_ = [
+ ("rowsize", ctypes.c_long),
+ ("linset", ctypes.POINTER(ctypes.c_ulong)),
+ ("colsize", ctypes.c_long),
+ ("representation", ctypes.c_int),
+ ("numbtype", ctypes.c_int),
+ ("matrix", ctypes.POINTER(ctypes.POINTER(mytype))),
+ ("objective", ctypes.c_int),
+ ("rowvec", ctypes.POINTER(mytype)),
+ ]
+
+# Define the input and output types for a bunch of libcdd functions.
+libcdd._Z15dd_CreateMatrixll.restype = ctypes.POINTER(dd_matrixdata)
+libcdd._Z9ddd_get_dPd.argtypes = [mytype]
+libcdd._Z9ddd_get_dPd.restype = ctypes.c_double
+
+libcdd._Z17dd_CopyGeneratorsP16dd_polyhedradata.argtypes = [
+ ctypes.POINTER(dd_polyhedradata)
+]
+libcdd._Z17dd_CopyGeneratorsP16dd_polyhedradata.restype = ctypes.POINTER(dd_matrixdata)
+
+libcdd._Z16dd_DDMatrix2PolyP13dd_matrixdataP12dd_ErrorType.argtypes = [
+ ctypes.POINTER(dd_matrixdata),
+ ctypes.POINTER(ctypes.c_int)
+]
+libcdd._Z16dd_DDMatrix2PolyP13dd_matrixdataP12dd_ErrorType.restype = (
+ ctypes.POINTER(dd_polyhedradata))
+
+libcdd._Z13dd_FreeMatrixP13dd_matrixdata.argtypes = [
+ ctypes.POINTER(dd_matrixdata)
+]
+
+libcdd._Z16dd_FreePolyhedraP16dd_polyhedradata.argtypes = [
+ ctypes.POINTER(dd_polyhedradata)
+]
+
+libcdd._Z9ddd_set_dPdd.argtypes = [
+ mytype,
+ ctypes.c_double
+]
+
+
+# Various enums.
+DD_INEQUALITY = 1
+DD_REAL = 1
+DD_NO_ERRORS = 17
+
+
+def dd_CreateMatrix(rows, cols):
+ return libcdd._Z15dd_CreateMatrixll(
+ ctypes.c_long(rows),
+ ctypes.c_long(cols))
+
+
+def dd_set_d(mytype_address, double_value):
+ libcdd._Z9ddd_set_dPdd(mytype_address,
+ ctypes.c_double(double_value))
+
+
+def dd_CopyGenerators(polyhedraptr):
+ return libcdd._Z17dd_CopyGeneratorsP16dd_polyhedradata(polyhedraptr)
+
+
+def dd_get_d(mytype_address):
+ return libcdd._Z9ddd_get_dPd(mytype_address)
+
+
+def dd_FreeMatrix(matrixptr):
+ libcdd._Z13dd_FreeMatrixP13dd_matrixdata(matrixptr)
+
+
+def dd_FreePolyhedra(polyhedraptr):
+ libcdd._Z16dd_FreePolyhedraP16dd_polyhedradata(polyhedraptr)
+
+
+def dd_DDMatrix2Poly(matrixptr):
+ error = ctypes.c_int()
+ polyhedraptr = libcdd._Z16dd_DDMatrix2PolyP13dd_matrixdataP12dd_ErrorType(
+ matrixptr,
+ ctypes.byref(error))
+
+ # Return None on error.
+ # The error values are enums, so they aren't exposed.
+ if error.value != NO_ERRORS:
+ # Dump out the errors to stderr
+ libcdd._Z21dd_WriteErrorMessagesP8_IO_FILE12dd_ErrorType(
+ ctypes.pythonapi.PyFile_AsFile(ctypes.py_object(sys.stdout)),
+ error)
+ dd_FreePolyhedra(polyhedraptr)
+ return None
+ return polyhedraptr
diff --git a/frc971/control_loops/python/polytope.py b/frc971/control_loops/python/polytope.py
new file mode 100644
index 0000000..e08a160
--- /dev/null
+++ b/frc971/control_loops/python/polytope.py
@@ -0,0 +1,224 @@
+#!/usr/bin/python
+
+"""
+Polyhedral set library.
+
+This library implements convex regions of the form H x <= k, where H, x, and k
+are matricies. It also provides convenient methods to find all the verticies.
+"""
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+
+import libcdd
+import numpy
+import string
+import sys
+
+
+def _PiecewiseConcat(*args):
+ """Concatenates strings inside lists, elementwise.
+
+ Given ['a', 's'] and ['d', 'f'], returns ['ad', 'sf']
+ """
+ return map(''.join, zip(*args))
+
+
+def _SplitAndPad(s):
+ """Splits a string on newlines, and pads the lines to be the same width."""
+ split_string = s.split('\n')
+ width = max(len(stringpiece) for stringpiece in split_string) + 1
+
+ padded_strings = [string.ljust(stringpiece, width, ' ')
+ for stringpiece in split_string]
+ return padded_strings
+
+
+def _PadHeight(padded_array, min_height):
+ """Adds lines of spaces to the top and bottom of an array symmetrically."""
+ height = len(padded_array)
+ if height < min_height:
+ pad_array = [' ' * len(padded_array[0])]
+ height_error = min_height - height
+ return (pad_array * ((height_error) / 2) +
+ padded_array +
+ pad_array * ((height_error + 1) / 2))
+ return padded_array
+
+
+class HPolytope(object):
+ """This object represents a H-polytope.
+
+ Polytopes are convex regions in n-dimensional space.
+ For H-polytopes, this is represented as the intersection of a set of half
+ planes. The mathematic equation that represents this is H x <= k.
+ """
+
+ def __init__(self, H, k):
+ """Constructs a H-polytope from the H and k matricies.
+
+ Args:
+ H: numpy.Matrix (n by k), where n is the number of constraints, and k is
+ the number of dimensions in the space. Does not copy the matrix.
+ k: numpy.Matrix (n by 1). Does not copy the matrix.
+ """
+ self._H = H
+ self._k = k
+
+ @property
+ def k(self):
+ """Returns the k in H x <= k."""
+ return self._k
+
+ @property
+ def H(self):
+ """Returns the H in H x <= k."""
+ return self._H
+
+ @property
+ def ndim(self):
+ """Returns the dimension of the set."""
+ return self._H.shape[1]
+
+ @property
+ def num_constraints(self):
+ """Returns the number of constraints defining the set."""
+ return self._k.shape[0]
+
+ def IsInside(self, point):
+ """Returns true if the point is inside the polytope, edges included."""
+ return (self._H * point <= self._k).all()
+
+ def Vertices(self):
+ """Returns a matrix with the vertices of the set in its rows."""
+ # TODO(aschuh): It would be better to write some small C/C++ function that
+ # does all of this and takes in a numpy array.
+ # The copy is expensive in Python and cheaper in C.
+
+ # Create an empty matrix with the correct size.
+ matrixptr = libcdd.dd_CreateMatrix(self.num_constraints, self.ndim + 1)
+ matrix = matrixptr.contents
+
+ try:
+ # Copy the data into the matrix.
+ for i in xrange(self.num_constraints):
+ libcdd.dd_set_d(matrix.matrix[i][0], self._k[i, 0])
+ for j in xrange(self.ndim):
+ libcdd.dd_set_d(matrix.matrix[i][j + 1], -self._H[i, j])
+
+ # Set enums to the correct values.
+ matrix.representation = libcdd.DD_INEQUALITY
+ matrix.numbtype = libcdd.DD_REAL
+
+ # TODO(aschuh): Set linearity if it is useful.
+ # This would be useful if we had any constraints saying B - A x = 0
+
+ # Build a Polyhedra
+ polyhedraptr = libcdd.dd_DDMatrix2Poly(matrixptr)
+
+ if not polyhedraptr:
+ return None
+
+ try:
+ # Return None on error.
+ # The error values are enums, so they aren't exposed.
+
+ # Magic happens here. Computes the vertices
+ vertex_matrixptr = libcdd.dd_CopyGenerators(
+ polyhedraptr)
+ vertex_matrix = vertex_matrixptr.contents
+
+ try:
+ # Count the number of vertices and rays in the result.
+ num_vertices = 0
+ num_rays = 0
+ for i in xrange(vertex_matrix.rowsize):
+ if libcdd.dd_get_d(vertex_matrix.matrix[i][0]) == 0:
+ num_rays += 1
+ else:
+ num_vertices += 1
+
+ # Build zeroed matricies for the new vertices and rays.
+ vertices = numpy.matrix(numpy.zeros((num_vertices,
+ vertex_matrix.colsize - 1)))
+ rays = numpy.matrix(numpy.zeros((num_rays,
+ vertex_matrix.colsize - 1)))
+
+ ray_index = 0
+ vertex_index = 0
+
+ # Copy the data out of the matrix.
+ for index in xrange(vertex_matrix.rowsize):
+ if libcdd.dd_get_d(vertex_matrix.matrix[index][0]) == 0.0:
+ for j in xrange(vertex_matrix.colsize - 1):
+ rays[ray_index, j] = libcdd.dd_get_d(
+ vertex_matrix.matrix[index][j + 1])
+ ray_index += 1
+ else:
+ for j in xrange(vertex_matrix.colsize - 1):
+ vertices[vertex_index, j] = libcdd.dd_get_d(
+ vertex_matrix.matrix[index][j + 1])
+ vertex_index += 1
+ finally:
+ # Free everything.
+ libcdd.dd_FreeMatrix(vertex_matrixptr)
+
+ finally:
+ libcdd.dd_FreePolyhedra(polyhedraptr)
+
+ finally:
+ libcdd.dd_FreeMatrix(matrixptr)
+
+ # Rays are unsupported right now. This may change in the future.
+ assert(rays.shape[0] == 0)
+
+ return vertices
+
+
+ def __str__(self):
+ """Returns a formatted version of the polytope.
+
+ The dump will look something like the following, which prints out the matrix
+ comparison.
+
+ [[ 1 0] [[12]
+ [-1 0] [[x0] <= [12]
+ [ 0 1] [x1]] [12]
+ [ 0 -1]] [12]]
+ """
+ height = max(self.ndim, self.num_constraints)
+
+ # Split the print up into 4 parts and concatenate them all.
+ H_strings = _PadHeight(_SplitAndPad(str(self.H)), height)
+ v_strings = _PadHeight(_SplitAndPad(str(self.k)), height)
+ x_strings = _PadHeight(self._MakeXStrings(), height)
+ cmp_strings = self._MakeCmpStrings(height)
+
+ return '\n'.join(_PiecewiseConcat(H_strings, x_strings,
+ cmp_strings, v_strings))
+
+ def _MakeXStrings(self):
+ """Builds an array of strings with constraint names in it for printing."""
+ x_strings = []
+ if self.ndim == 1:
+ x_strings = ["[[x0]] "]
+ else:
+ for index in xrange(self.ndim):
+ if index == 0:
+ x = "[[x%d] " % index
+ elif index == self.ndim - 1:
+ x = " [x%d]] " % index
+ else:
+ x = " [x%d] " % index
+ x_strings.append(x)
+ return x_strings
+
+ def _MakeCmpStrings(self, height):
+ """Builds an array of strings with the comparison in it for printing."""
+ cmp_strings = []
+ for index in xrange(height):
+ if index == (height - 1) / 2:
+ cmp_strings.append("<= ")
+ else:
+ cmp_strings.append(" ")
+ return cmp_strings
diff --git a/frc971/control_loops/python/polytope_test.py b/frc971/control_loops/python/polytope_test.py
new file mode 100755
index 0000000..9a35ebe
--- /dev/null
+++ b/frc971/control_loops/python/polytope_test.py
@@ -0,0 +1,192 @@
+#!/usr/bin/python
+
+import numpy
+from numpy.testing import *
+import polytope
+import unittest
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+def MakePoint(*args):
+ """Makes a point from a set of arguments."""
+ return numpy.matrix([[arg] for arg in args])
+
+class TestHPolytope(unittest.TestCase):
+ def setUp(self):
+ """Builds a simple box polytope."""
+ self.H = numpy.matrix([[1, 0],
+ [-1, 0],
+ [0, 1],
+ [0, -1]])
+ self.k = numpy.matrix([[12],
+ [12],
+ [12],
+ [12]])
+ self.p = polytope.HPolytope(self.H, self.k)
+
+ def test_Hk(self):
+ """Tests that H and k are saved correctly."""
+ assert_array_equal(self.p.H, self.H)
+ assert_array_equal(self.p.k, self.k)
+
+ def test_IsInside(self):
+ """Tests IsInside for various points."""
+ inside_points = [
+ MakePoint(0, 0),
+ MakePoint(6, 6),
+ MakePoint(12, 6),
+ MakePoint(-6, 10)]
+ outside_points = [
+ MakePoint(14, 0),
+ MakePoint(-14, 0),
+ MakePoint(0, 14),
+ MakePoint(0, -14),
+ MakePoint(14, -14)]
+
+ for inside_point in inside_points:
+ self.assertTrue(self.p.IsInside(inside_point),
+ msg='Point is' + str(inside_point))
+
+ for outside_point in outside_points:
+ self.assertFalse(self.p.IsInside(outside_point),
+ msg='Point is' + str(outside_point))
+
+ def AreVertices(self, p, vertices):
+ """Checks that all the vertices are on corners of the set."""
+ for i in xrange(vertices.shape[0]):
+ # Check that all the vertices have the correct number of active
+ # constraints.
+ lmda = p.H * vertices[i,:].T - p.k
+ num_active_constraints = 0
+ for j in xrange(lmda.shape[0]):
+ # Verify that the constraints are either active, or not violated.
+ if numpy.abs(lmda[j, 0]) <= 1e-9:
+ num_active_constraints += 1
+ else:
+ self.assertLessEqual(lmda[j, 0], 0.0)
+
+ self.assertEqual(p.ndim, num_active_constraints)
+
+ def HasSamePoints(self, expected, actual):
+ """Verifies that the points in expected are in actual."""
+ found_points = set()
+ self.assertEqual(expected.shape, actual.shape)
+ for index in xrange(expected.shape[0]):
+ expected_point = expected[index, :]
+ for actual_index in xrange(actual.shape[0]):
+ actual_point = actual[actual_index, :]
+ if numpy.abs(expected_point - actual_point).max() <= 1e-4:
+ found_points.add(actual_index)
+ break
+
+ self.assertEqual(len(found_points), actual.shape[0],
+ msg="Expected:\n" + str(expected) + "\nActual:\n" + str(actual))
+
+ def test_Skewed_Nonsym_Vertices(self):
+ """Tests the vertices of a severely skewed space."""
+ self.H = numpy.matrix([[10, -1],
+ [-1, -1],
+ [-1, 10],
+ [10, 10]])
+ self.k = numpy.matrix([[2],
+ [2],
+ [2],
+ [2]])
+ self.p = polytope.HPolytope(self.H, self.k)
+ vertices = self.p.Vertices()
+ self.AreVertices(self.p, vertices)
+
+ self.HasSamePoints(
+ numpy.matrix([[0., 0.2],
+ [0.2, 0.],
+ [-2., 0.],
+ [0., -2.]]),
+ vertices)
+
+ def test_Vertices_Nonsym(self):
+ """Tests the vertices of a nonsymetric space."""
+ self.k = numpy.matrix([[6],
+ [12],
+ [2],
+ [10]])
+ self.p = polytope.HPolytope(self.H, self.k)
+ vertices = self.p.Vertices()
+ self.AreVertices(self.p, vertices)
+
+ self.HasSamePoints(
+ numpy.matrix([[6., 2.],
+ [6., -10.],
+ [-12., -10.],
+ [-12., 2.]]),
+ vertices)
+
+ def test_Vertices(self):
+ """Tests the vertices of a nonsymetric space."""
+ self.HasSamePoints(self.p.Vertices(),
+ numpy.matrix([[12., 12.],
+ [12., -12.],
+ [-12., -12.],
+ [-12., 12.]]))
+
+ def test_concat(self):
+ """Tests that the concat function works for simple inputs."""
+ self.assertEqual(["asd", "qwe"],
+ polytope._PiecewiseConcat(["a", "q"],
+ ["s", "w"],
+ ["d", "e"]))
+
+ def test_str(self):
+ """Verifies that the str method works for the provided p."""
+ self.assertEqual('[[ 1 0] [[12] \n'
+ ' [-1 0] [[x0] <= [12] \n'
+ ' [ 0 1] [x1]] [12] \n'
+ ' [ 0 -1]] [12]] ',
+ str(self.p))
+
+ def MakePWithDims(self, num_constraints, num_dims):
+ """Makes a zeroed out polytope with the correct size."""
+ self.p = polytope.HPolytope(
+ numpy.matrix(numpy.zeros((num_constraints, num_dims))),
+ numpy.matrix(numpy.zeros((num_constraints, 1))))
+
+ def test_few_constraints_odd_constraint_even_dims_str(self):
+ """Tests printing out the set with odd constraints and even dimensions."""
+ self.MakePWithDims(num_constraints=5, num_dims=2)
+ self.assertEqual('[[ 0. 0.] [[ 0.] \n'
+ ' [ 0. 0.] [[x0] [ 0.] \n'
+ ' [ 0. 0.] [x1]] <= [ 0.] \n'
+ ' [ 0. 0.] [ 0.] \n'
+ ' [ 0. 0.]] [ 0.]] ',
+ str(self.p))
+
+ def test_few_constraints_odd_constraint_small_dims_str(self):
+ """Tests printing out the set with odd constraints and odd dimensions."""
+ self.MakePWithDims(num_constraints=5, num_dims=1)
+ self.assertEqual('[[ 0.] [[ 0.] \n'
+ ' [ 0.] [ 0.] \n'
+ ' [ 0.] [[x0]] <= [ 0.] \n'
+ ' [ 0.] [ 0.] \n'
+ ' [ 0.]] [ 0.]] ',
+ str(self.p))
+
+ def test_few_constraints_odd_constraint_odd_dims_str(self):
+ """Tests printing out the set with odd constraints and odd dimensions."""
+ self.MakePWithDims(num_constraints=5, num_dims=3)
+ self.assertEqual('[[ 0. 0. 0.] [[ 0.] \n'
+ ' [ 0. 0. 0.] [[x0] [ 0.] \n'
+ ' [ 0. 0. 0.] [x1] <= [ 0.] \n'
+ ' [ 0. 0. 0.] [x2]] [ 0.] \n'
+ ' [ 0. 0. 0.]] [ 0.]] ',
+ str(self.p))
+
+ def test_many_constraints_even_constraint_odd_dims_str(self):
+ """Tests printing out the set with even constraints and odd dimensions."""
+ self.MakePWithDims(num_constraints=2, num_dims=3)
+ self.assertEqual('[[ 0. 0. 0.] [[x0] [[ 0.] \n'
+ ' [ 0. 0. 0.]] [x1] <= [ 0.]] \n'
+ ' [x2]] ',
+ str(self.p))
+
+
+if __name__ == '__main__':
+ unittest.main()
diff --git a/frc971/crio/build.sh b/frc971/crio/build.sh
new file mode 100755
index 0000000..ec04978
--- /dev/null
+++ b/frc971/crio/build.sh
@@ -0,0 +1,3 @@
+#!/bin/bash
+
+../../aos/build/build.sh crio crio.gyp no $1
diff --git a/frc971/crio/crio.gyp b/frc971/crio/crio.gyp
new file mode 100644
index 0000000..236ec14
--- /dev/null
+++ b/frc971/crio/crio.gyp
@@ -0,0 +1,54 @@
+{
+ 'targets': [
+ {
+# The WPILib code that we've modified.
+ 'target_name': 'WPILib_changes',
+ 'type': 'static_library',
+ 'sources': [
+ '<(AOS)/externals/WPILib/WPILib/DriverStationLCD.cpp',
+ '<(AOS)/externals/WPILib/WPILib/Synchronized.cpp',
+ '<(AOS)/externals/WPILib/WPILib/DriverStation.cpp',
+ '<(AOS)/externals/WPILib/WPILib/Notifier.cpp',
+ '<(AOS)/externals/WPILib/WPILib/MotorSafetyHelper.cpp',
+ '<(AOS)/externals/WPILib/WPILib/Resource.cpp',
+ '<(AOS)/externals/WPILib/WPILib/SolenoidBase.cpp',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):WPILib',
+ ],
+ 'cflags!': ['-Werror'],
+ },
+ {
+ 'target_name': 'user_program',
+ 'type': 'static_library',
+ 'sources': [
+ 'main.cc',
+ ],
+ 'dependencies': [
+ '../input/input.gyp:SensorReader',
+ '../input/input.gyp:SensorWriter',
+ '../output/output.gyp:MotorWriter',
+ '../output/output.gyp:SensorSender',
+ 'WPILib_changes',
+ '<(EXTERNALS):WPILib',
+ '<(AOS)/common/messages/messages.gyp:aos_queues',
+ ],
+ },
+ {
+ 'target_name': 'FRC_UserProgram',
+ 'type': 'shared_library',
+ 'dependencies': [
+ 'user_program'
+ ],
+ },
+ {
+ 'target_name': 'FRC_UserProgram_WithTests',
+ 'type': 'shared_library',
+ 'dependencies': [
+ 'user_program',
+ # For testing.
+ '<(AOS)/build/aos_all.gyp:Crio',
+ ],
+ },
+ ],
+}
diff --git a/frc971/crio/main.cc b/frc971/crio/main.cc
new file mode 100644
index 0000000..e814b97
--- /dev/null
+++ b/frc971/crio/main.cc
@@ -0,0 +1,19 @@
+#include "aos/crio/controls/ControlsManager.h"
+
+#include "aos/crio/motor_server/CRIOControlLoopRunner.h"
+
+namespace frc971 {
+
+class MyRobot : public ::aos::crio::ControlsManager {
+ public:
+ virtual void RegisterControlLoops() {
+ //::aos::crio::CRIOControlLoopRunner::AddControlLoop(&shooter_);
+ }
+
+ private:
+ //::frc971::control_loops::ShooterMotor shooter_;
+};
+
+} // namespace frc971
+
+START_ROBOT_CLASS(::frc971::MyRobot);
diff --git a/frc971/frc971.gyp b/frc971/frc971.gyp
new file mode 100644
index 0000000..ff43949
--- /dev/null
+++ b/frc971/frc971.gyp
@@ -0,0 +1,14 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'common',
+ 'type': 'static_library',
+ 'sources': [
+ 'constants.cpp',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ }
+ ],
+}
diff --git a/frc971/input/AutoMode.act b/frc971/input/AutoMode.act
new file mode 100644
index 0000000..b7b98c3
--- /dev/null
+++ b/frc971/input/AutoMode.act
@@ -0,0 +1,7 @@
+args automode_args {
+};
+status automode_status {
+};
+//has OnEnd;
+//has OnStart;
+priority 99;
diff --git a/frc971/input/AutoMode.cc b/frc971/input/AutoMode.cc
new file mode 100644
index 0000000..254d6b6
--- /dev/null
+++ b/frc971/input/AutoMode.cc
@@ -0,0 +1,15 @@
+#include "frc971/input/AutoMode.q.h"
+
+#include <stdlib.h>
+#include <stdio.h>
+#include <unistd.h>
+
+#include "aos/common/control_loop/Timing.h"
+
+namespace frc971 {
+
+void AutoMode_t::DoAction() {
+ Sleep(10); // wait until it ends
+}
+
+} // namespace frc971
diff --git a/frc971/input/GyroReader.cc b/frc971/input/GyroReader.cc
new file mode 100644
index 0000000..a6e1d00
--- /dev/null
+++ b/frc971/input/GyroReader.cc
@@ -0,0 +1,50 @@
+#include <unistd.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <fcntl.h>
+
+#include "aos/aos_core.h"
+
+#include "frc971/queues/GyroAngle.q.h"
+
+#define M_PI 3.14159265358979323846264338327
+
+using frc971::sensors::gyro;
+
+int main(){
+ aos::Init();
+ int fd = open("/dev/aschuh0", O_RDONLY);
+ int rate_limit = 0;
+ if (fd < 0) {
+ LOG(ERROR, "No Gyro found.\n");
+ } else {
+ LOG(INFO, "Gyro now connected\n");
+ }
+
+ while (true) {
+ int64_t gyro_value;
+ if (read(fd, (void *)&gyro_value, sizeof(gyro_value)) != sizeof(gyro_value)) {
+ LOG(ERROR, "Could not read gyro errno: %d\n", errno);
+ if (errno == ENODEV || errno == EBADF) {
+ close(fd);
+ while (1) {
+ usleep(1000);
+ fd = open("/dev/aschuh0", O_RDONLY);
+ if (fd > 0) {
+ LOG(INFO, "Found gyro again\n");
+ break;
+ }
+ }
+ }
+ continue;
+ }
+ rate_limit ++;
+ if (rate_limit > 10) {
+ LOG(DEBUG, "Gyro is %d\n", (int)(gyro_value / 16));
+ rate_limit = 0;
+ }
+ gyro.MakeWithBuilder().angle(gyro_value / 16.0 / 1000.0 / 180.0 * M_PI).Send();
+ }
+
+ aos::Cleanup();
+}
diff --git a/frc971/input/JoystickReader.cc b/frc971/input/JoystickReader.cc
new file mode 100644
index 0000000..e0cfbac
--- /dev/null
+++ b/frc971/input/JoystickReader.cc
@@ -0,0 +1,100 @@
+#include <stdio.h>
+#include <string.h>
+#include <unistd.h>
+#include <math.h>
+
+#include "aos/aos_core.h"
+#include "aos/atom_code/input/FRCComm.h"
+#include "aos/atom_code/input/JoystickInput.h"
+
+#include "frc971/input/AutoMode.q.h"
+#include "frc971/control_loops/DriveTrain.q.h"
+#include "frc971/queues/GyroAngle.q.h"
+#include "frc971/queues/Piston.q.h"
+
+using ::frc971::control_loops::drivetrain;
+using ::frc971::control_loops::shifters;
+using ::frc971::sensors::gyro;
+
+namespace frc971 {
+
+class JoystickReader : public aos::JoystickInput {
+ public:
+ JoystickReader() : aos::JoystickInput() {
+ shifters.MakeWithBuilder().set(true).Send();
+ }
+
+ virtual void RunIteration() {
+ static bool is_high_gear = false;
+
+ if (Pressed(0, AUTONOMOUS)) {
+ if (PosEdge(0, ENABLED)){
+ LOG(INFO, "Starting auto mode\n");
+ AutoMode.Start();
+ }
+ if (NegEdge(0, ENABLED)) {
+ LOG(INFO, "Stopping auto mode\n");
+ AutoMode.Stop();
+ }
+ } else { // teleop
+ bool is_control_loop_driving = false;
+ double left_goal = 0.0;
+ double right_goal = 0.0;
+ const double wheel = control_data_.stick0Axis1 / 127.0;
+ const double throttle = -control_data_.stick1Axis2 / 127.0;
+ const double kThrottleGain = 1.0 / 2.5;
+ if (Pressed(0, 7) || Pressed(0, 11)) {
+ static double distance = 0.0;
+ static double angle = 0.0;
+ static double filtered_goal_distance = 0.0;
+ if (PosEdge(0, 7) || PosEdge(0, 11)) {
+ if (drivetrain.position.FetchLatest() && gyro.FetchLatest()) {
+ distance = (drivetrain.position->left_encoder +
+ drivetrain.position->right_encoder) / 2.0
+ - throttle * kThrottleGain / 2.0;
+ angle = gyro->angle;
+ filtered_goal_distance = distance;
+ }
+ }
+ is_control_loop_driving = true;
+
+ //const double gyro_angle = Gyro.View().angle;
+ const double goal_theta = angle - wheel * 0.27;
+ const double goal_distance = distance + throttle * kThrottleGain;
+ const double robot_width = 22.0 / 100.0 * 2.54;
+ const double kMaxVelocity = 0.6;
+ if (goal_distance > kMaxVelocity * 0.02 + filtered_goal_distance) {
+ filtered_goal_distance += kMaxVelocity * 0.02;
+ } else if (goal_distance < -kMaxVelocity * 0.02 + filtered_goal_distance) {
+ filtered_goal_distance -= kMaxVelocity * 0.02;
+ } else {
+ filtered_goal_distance = goal_distance;
+ }
+ left_goal = filtered_goal_distance - robot_width * goal_theta / 2.0;
+ right_goal = filtered_goal_distance + robot_width * goal_theta / 2.0;
+ is_high_gear = false;
+
+ LOG(DEBUG, "Left goal %f Right goal %f\n", left_goal, right_goal);
+ }
+ if (!(drivetrain.goal.MakeWithBuilder()
+ .steering(wheel)
+ .throttle(throttle)
+ .highgear(is_high_gear).quickturn(Pressed(0, 5))
+ .control_loop_driving(is_control_loop_driving)
+ .left_goal(left_goal).right_goal(right_goal).Send())) {
+ LOG(WARNING, "sending stick values failed\n");
+ }
+
+ if (PosEdge(1, 1)) {
+ is_high_gear = false;
+ }
+ if (PosEdge(1, 3)) {
+ is_high_gear = true;
+ }
+ }
+ }
+};
+
+} // namespace frc971
+
+AOS_RUN(frc971::JoystickReader)
diff --git a/frc971/input/SensorReader.cc b/frc971/input/SensorReader.cc
new file mode 100644
index 0000000..fd14df4
--- /dev/null
+++ b/frc971/input/SensorReader.cc
@@ -0,0 +1,44 @@
+#define __STDC_LIMIT_MACROS
+
+#include <arpa/inet.h>
+
+#include "aos/aos_core.h"
+#include "aos/common/inttypes.h"
+#include "aos/common/input/SensorInput.h"
+
+#include "frc971/control_loops/DriveTrain.q.h"
+#include "frc971/queues/sensor_values.h"
+
+#define M_PI 3.14159265358979323846
+
+using ::frc971::control_loops::drivetrain;
+
+namespace frc971 {
+
+namespace {
+inline double drivetrain_translate(int32_t in) {
+ // TODO(2013) fix the math
+ return static_cast<double>(in) / (256.0 * 4.0 * 44.0 / 32.0) *
+ (3.5 * 2.54 / 100.0 * M_PI);
+}
+} // namespace
+
+class SensorReader : public aos::SensorInput<sensor_values> {
+ virtual void RunIteration(sensor_values &sensors) {
+ for (size_t i = 0; i < sizeof(sensors.encoders) / sizeof(sensors.encoders[0]); ++i) {
+ sensors.encoders[i] = ntohl(sensors.encoders[i]);
+ }
+
+ // TODO(aschuh): Convert to meters.
+ const double left_encoder = drivetrain_translate(sensors.lencoder);
+ const double right_encoder = drivetrain_translate(sensors.rencoder);
+ drivetrain.position.MakeWithBuilder()
+ .left_encoder(left_encoder)
+ .right_encoder(right_encoder)
+ .Send();
+ }
+};
+
+} // namespace frc971
+
+AOS_RUN(frc971::SensorReader)
diff --git a/frc971/input/SensorWriter.cc b/frc971/input/SensorWriter.cc
new file mode 100644
index 0000000..1fb34db
--- /dev/null
+++ b/frc971/input/SensorWriter.cc
@@ -0,0 +1,40 @@
+#include <arpa/inet.h>
+
+#include "WPILib/Task.h"
+#include "WPILib/Encoder.h"
+#include "WPILib/DigitalInput.h"
+#include "WPILib/Counter.h"
+
+#include "aos/aos_core.h"
+#include "aos/crio/motor_server/SensorOutput.h"
+#include "aos/common/inttypes.h"
+#include "aos/common/mutex.h"
+#include "aos/crio/shared_libs/interrupt_notifier.h"
+
+#include "frc971/queues/sensor_values.h"
+
+using ::aos::MutexLocker;
+
+namespace frc971 {
+
+class SensorWriter : public aos::SensorOutput<sensor_values> {
+ Encoder lencoder;
+ Encoder rencoder;
+
+ public:
+ SensorWriter() : lencoder(1, 2), rencoder(3, 4) {
+ lencoder.Start();
+ rencoder.Start();
+
+ printf("frc971::SensorWriter started\n");
+ }
+
+ virtual void RunIteration(sensor_values &vals) {
+ vals.lencoder = htonl(-lencoder.GetRaw());
+ vals.rencoder = -htonl(-rencoder.GetRaw());
+ }
+};
+
+} // namespace frc971
+
+AOS_RUN(frc971::SensorWriter)
diff --git a/frc971/input/input.gyp b/frc971/input/input.gyp
new file mode 100644
index 0000000..43f591a
--- /dev/null
+++ b/frc971/input/input.gyp
@@ -0,0 +1,80 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'actions',
+ 'type': 'static_library',
+ 'sources': ['AutoMode.act'],
+ 'variables': {
+ 'header_path': 'frc971/input',
+ },
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(AOS)/common/common.gyp:controls',
+ ],
+ 'includes': ['../../aos/build/queues.gypi'],
+ },
+ {
+ 'target_name': 'JoystickReader',
+ 'type': 'executable',
+ 'sources': [
+ 'JoystickReader.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(AOS)/atom_code/input/input.gyp:joystick',
+ '<(AOS)/common/network/network.gyp:socket',
+ 'actions',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:control_loops',
+ '<(DEPTH)/frc971/queues/queues.gyp:queues',
+ ],
+ },
+ {
+ 'target_name': 'SensorReader',
+ 'type': '<(aos_target)',
+ 'sources': [
+ 'SensorReader.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:control_loops',
+ '<(DEPTH)/frc971/queues/queues.gyp:queues',
+ '<(AOS)/common/network/network.gyp:socket',
+ ],
+ },
+ {
+ 'target_name': 'SensorWriter',
+ 'type': '<(aos_target)',
+ 'sources': [
+ 'SensorWriter.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:control_loops',
+ ],
+ },
+ {
+ 'target_name': 'GyroReader',
+ 'type': 'executable',
+ 'sources': [
+ 'GyroReader.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(DEPTH)/frc971/queues/queues.gyp:queues',
+ ],
+ },
+ {
+ 'target_name': 'AutoMode',
+ 'type': 'executable',
+ 'sources': [
+ 'AutoMode.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:control_loops',
+ '<(DEPTH)/frc971/queues/queues.gyp:queues',
+ 'actions',
+ ],
+ },
+ ],
+}
diff --git a/frc971/output/AtomMotorWriter.cc b/frc971/output/AtomMotorWriter.cc
new file mode 100644
index 0000000..d0bf6f7
--- /dev/null
+++ b/frc971/output/AtomMotorWriter.cc
@@ -0,0 +1,40 @@
+#include <stdio.h>
+#include <string.h>
+#include <unistd.h>
+
+#include "aos/aos_core.h"
+#include "aos/common/network/SendSocket.h"
+#include "aos/common/control_loop/Timing.h"
+#include "aos/common/messages/RobotState.q.h"
+#include "aos/atom_code/output/MotorOutput.h"
+
+#include "frc971/queues/Piston.q.h"
+#include "frc971/control_loops/DriveTrain.q.h"
+#include "frc971/constants.h"
+
+using ::frc971::control_loops::drivetrain;
+using ::frc971::control_loops::shifters;
+
+namespace frc971 {
+namespace output {
+
+class MotorWriter : public aos::MotorOutput {
+ void RunIteration() {
+ if (drivetrain.output.FetchLatest()) {
+ AddMotor(TALON, 7, -drivetrain.output->left_voltage / 12.0);
+ AddMotor(TALON, 4, drivetrain.output->right_voltage / 12.0);
+ } else {
+ AddMotor(TALON, 7, 0.0f);
+ AddMotor(TALON, 4, 0.0f);
+ }
+
+ if (shifters.FetchLatest()) {
+ AddSolenoid(1, shifters->set);
+ }
+ }
+};
+
+} // namespace output
+} // namespace frc971
+
+AOS_RUN(frc971::output::MotorWriter)
diff --git a/frc971/output/CRIOMotorWriter.cc b/frc971/output/CRIOMotorWriter.cc
new file mode 100644
index 0000000..b85ac4b
--- /dev/null
+++ b/frc971/output/CRIOMotorWriter.cc
@@ -0,0 +1,15 @@
+#include "WPILib/Victor.h"
+
+#include "aos/crio/motor_server/MotorOutput.h"
+#include "aos/aos_core.h"
+
+namespace frc971 {
+
+class MotorWriter : public aos::MotorOutput {
+ virtual void RunIteration() {
+ }
+};
+
+} // namespace frc971
+
+AOS_RUN(frc971::MotorWriter)
diff --git a/frc971/output/CameraServer.cc b/frc971/output/CameraServer.cc
new file mode 100644
index 0000000..96f698d
--- /dev/null
+++ b/frc971/output/CameraServer.cc
@@ -0,0 +1,81 @@
+#include <string.h>
+
+#include "aos/aos_core.h"
+#include "aos/atom_code/output/HTTPServer.h"
+#include "aos/atom_code/output/evhttp_ctemplate_emitter.h"
+#include "ctemplate/template.h"
+
+#include "frc971/constants.h"
+
+RegisterTemplateFilename(ROBOT_HTML, "robot.html.tpl");
+
+namespace frc971 {
+
+const char *const kPath = "/home/driver/robot_code/bin/";
+//const char *const kPath = "/home/brians/Desktop/git_frc971/2012/trunk/src/frc971/output";
+
+class CameraServer : public aos::http::HTTPServer {
+ public:
+ CameraServer() : HTTPServer(kPath, 8080), buf_(NULL) {
+ AddPage<CameraServer>("/robot.html", &CameraServer::RobotHTML, this);
+ }
+
+ private:
+ evbuffer *buf_;
+ bool Setup(evhttp_request *request, const char *content_type) {
+ if (evhttp_add_header(evhttp_request_get_output_headers(request),
+ "Content-Type", content_type) == -1) {
+ LOG(WARNING, "adding Content-Type failed\n");
+ evhttp_send_error(request, HTTP_INTERNAL, NULL);
+ return false;
+ }
+ if (buf_ == NULL) buf_ = evbuffer_new();
+ if (buf_ == NULL) {
+ LOG(WARNING, "evbuffer_new() failed\n");
+ evhttp_send_error(request, HTTP_INTERNAL, NULL);
+ return false;
+ }
+ return true;
+ }
+ void RobotHTML(evhttp_request *request) {
+ if (!Setup(request, "text/html")) return;
+
+ ctemplate::TemplateDictionary dict(ROBOT_HTML);
+ const char *host = evhttp_find_header(
+ evhttp_request_get_input_headers(request), "Host");
+ if (host == NULL) {
+ evhttp_send_error(request, HTTP_BADREQUEST, "no Host header");
+ return;
+ }
+ const char *separator = strchrnul(host, ':');
+ size_t length = separator - host;
+ // Don't include the last ':' (or the terminating '\0') or anything else
+ // after it.
+ dict.SetValue("HOST", ctemplate::TemplateString(host, length));
+
+ int center;
+ if (!constants::camera_center(¢er)) {
+ evhttp_send_error(request, HTTP_INTERNAL, NULL);
+ return;
+ }
+ dict.SetIntValue("CENTER", center);
+
+ aos::http::EvhttpCtemplateEmitter emitter(buf_);
+ if (!ctemplate::ExpandTemplate(ROBOT_HTML, ctemplate::STRIP_WHITESPACE,
+ &dict, &emitter)) {
+ LOG(ERROR, "expanding the template failed\n");
+ evhttp_send_error(request, HTTP_INTERNAL, NULL);
+ return;
+ }
+ if (emitter.error()) {
+ evhttp_send_error(request, HTTP_INTERNAL, NULL);
+ return;
+ }
+ evhttp_send_reply(request, HTTP_OK, NULL, buf_);
+ }
+};
+
+} // namespace frc971
+
+AOS_RUN_NRT(frc971::CameraServer)
+
diff --git a/frc971/output/SensorSender.cc b/frc971/output/SensorSender.cc
new file mode 100644
index 0000000..e2d2e51
--- /dev/null
+++ b/frc971/output/SensorSender.cc
@@ -0,0 +1,5 @@
+#include "aos/crio/motor_server/SensorSender.h"
+#include "frc971/queues/sensor_values.h"
+
+AOS_RUN_FORK(aos::SensorSender<frc971::sensor_values>, "971SS", 100)
+
diff --git a/frc971/output/output.gyp b/frc971/output/output.gyp
new file mode 100644
index 0000000..6cb28d1
--- /dev/null
+++ b/frc971/output/output.gyp
@@ -0,0 +1,59 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'CameraServer',
+ 'type': 'executable',
+ 'sources': [
+ 'CameraServer.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(AOS)/atom_code/output/output.gyp:http_server',
+ '../frc971.gyp:common',
+ ],
+ 'copies': [
+ {
+ 'destination': '<(rsync_dir)',
+ 'files': [
+ 'robot.html.tpl',
+ ],
+ },
+ ],
+ },
+ {
+ 'target_name': 'MotorWriter',
+ 'type': '<(aos_target)',
+ 'conditions': [
+ ['OS=="atom"', {
+ 'sources': ['AtomMotorWriter.cc'],
+ 'dependencies': [
+ '../frc971.gyp:common',
+ '<(AOS)/atom_code/output/output.gyp:motor_output',
+ '<(AOS)/atom_code/messages/messages.gyp:messages',
+ ],
+ }, {
+ 'sources': ['CRIOMotorWriter.cc'],
+ }
+ ],
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(AOS)/common/common.gyp:controls',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:control_loops',
+ '<(DEPTH)/frc971/queues/queues.gyp:queues',
+ '<(AOS)/common/network/network.gyp:socket',
+ ],
+ },
+ {
+ 'target_name': 'SensorSender',
+ 'type': '<(aos_target)',
+ 'sources': [
+ 'SensorSender.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:libaos',
+ '<(AOS)/common/network/network.gyp:socket',
+ ],
+ },
+ ],
+}
diff --git a/frc971/output/robot.html.tpl b/frc971/output/robot.html.tpl
new file mode 100644
index 0000000..7ae51a6
--- /dev/null
+++ b/frc971/output/robot.html.tpl
@@ -0,0 +1,56 @@
+<!DOCTYPE HTML>
+<html>
+ <head>
+ <title>971 Camera Code: Robot Stream</title>
+ <style type="text/css">
+ #body {
+ display: block;
+ margin: 0px;
+ margin-top: 0px;
+ margin-right: 0px;
+ margin-bottom: 0px;
+ margin-left: 0px;
+ }
+ #img {
+ position: absolute;
+ left: 50%;
+ top: 0%;
+ margin: 0 0 0 -320px;
+ }
+ #center {
+ left: 50%;
+ position: absolute;
+ width: 2px;
+ height: 100%;
+ background-color: red;
+ }
+ #middle {
+ top: 240px;
+ margin-top: -1px;
+ width: 100%;
+ position: absolute;
+ height: 2px;
+ background-color: red;
+ }
+ #footer {
+ top: 482px;
+ left: 10px;
+ position: absolute;
+ }
+ #center {
+ margin-left: {{CENTER}}px;
+ }
+ </style>
+ </head>
+ <body id="body">
+ <img id="img" src="http://{{HOST}}:9714" />
+ <div id="center"></div>
+ <div id="middle"></div>
+ <div id="footer">
+ <!--<form>
+ <input type="button" value="Camera Controls"
+ onclick="window.open('control.htm', 'Camera_Controls')">
+ </form>-->
+ </div>
+ </body>
+</html>
diff --git a/frc971/queues/GyroAngle.q b/frc971/queues/GyroAngle.q
new file mode 100644
index 0000000..bcf3ac4
--- /dev/null
+++ b/frc971/queues/GyroAngle.q
@@ -0,0 +1,7 @@
+package frc971.sensors;
+
+message Gyro {
+ double angle;
+};
+
+queue Gyro gyro;
diff --git a/frc971/queues/Piston.q b/frc971/queues/Piston.q
new file mode 100644
index 0000000..0819567
--- /dev/null
+++ b/frc971/queues/Piston.q
@@ -0,0 +1,7 @@
+package frc971.control_loops;
+
+message Piston {
+ bool set;
+};
+
+queue Piston shifters;
diff --git a/frc971/queues/queues.gyp b/frc971/queues/queues.gyp
new file mode 100644
index 0000000..70ed873
--- /dev/null
+++ b/frc971/queues/queues.gyp
@@ -0,0 +1,40 @@
+{
+ 'variables': {
+ 'queue_files': [
+ 'GyroAngle.q',
+ 'Piston.q',
+ ]
+ },
+ 'targets': [
+ {
+ 'target_name': 'queues',
+ 'type': 'static_library',
+ 'sources': ['<@(queue_files)'],
+ 'variables': {
+ 'header_path': 'frc971/queues',
+ },
+ 'dependencies': [
+ '<(AOS)/common/common.gyp:queues',
+ '<(AOS)/build/aos.gyp:libaos',
+ ],
+ 'includes': ['../../aos/build/queues.gypi'],
+ },
+ {
+ 'target_name': 'frc971_queues_so',
+ 'type': 'loadable_module',
+ 'sources': ['<@(queue_files)'],
+ 'variables': {
+ 'header_path': 'frc971/queues',
+ },
+ 'dependencies': [
+ '<(AOS)/build/aos.gyp:aos_shared_lib',
+ ],
+ 'direct_dependent_settings': {
+ 'variables': {
+ 'jni_libs': ['frc971_queues_so'],
+ },
+ },
+ 'includes': ['../../aos/build/queues.gypi'],
+ },
+ ],
+}
diff --git a/frc971/queues/sensor_values.h b/frc971/queues/sensor_values.h
new file mode 100644
index 0000000..16d6890
--- /dev/null
+++ b/frc971/queues/sensor_values.h
@@ -0,0 +1,22 @@
+#ifndef __COMMON_SENSOR_VALUES_H_
+#define __COMMON_SENSOR_VALUES_H_
+
+#include <stdint.h>
+
+namespace frc971 {
+
+struct sensor_values {
+ union {
+ struct {
+ int32_t lencoder, rencoder;
+ };
+ uint32_t encoders[2];
+ };
+
+ // TODO(2013) all the rest
+};
+
+} // namespace frc971
+
+#endif
+