Massachusetts Institute of Technology Unmanned Aerial Vehicle Team

Size: px
Start display at page:

Download "Massachusetts Institute of Technology Unmanned Aerial Vehicle Team"

Transcription

1 . Massachusetts Institute of Technology Unmanned Aerial Vehicle Team Jonathan Downey, Buddy Michini Matt Doherty, Carl Engel, Jacob Katz, Karl Kulling 2006 AUVSI Student UAV Competition Journal Paper, Submitted June 1, 2006 Abstract This journal paper gives an overview of the Project AARES design process. The aircraft was designed to meet the need of modern UAVs to adapt to rapidly changing functional requirements. The modular, flexible design lends itself to the rapid development of all systems involved. Avionics, control architecture, navigation autonomy, and ground station support were custom-designed by students to meet the AUVSI mission requirements as well as future challenges. The result is a highly-capable UAV able to complete the competition objectives.

2 Contents 1 Introduction 1 2 Design Overview 1 3 Airframe 2 4 Avionics Requirements Rapid Prototyping of Avionics General Architecture Modular Hardware Power Module Inertial Measurement Unit RF Transceiver GPS Receiver Module RC Receiver Air Data Module Quad Actuator Modular Software Testing Individual Board Testing Networked Ground Testing Flight Testing Controls Modeling Numerical Simulation Controller Design Final Controller Architecture Discretization and Code Generation Autonomy Navigation Algorithm Mission Execution Contingency Operations Hardware-in-the-Loop Simulator Ground Control Station 15 8 Safety Safety Override Power Systems RFI Protection Conclusion 18

3 List of Figures 1 Photograph of airframe RF Transceiver RC Receiver Air Data Module Quad Actuator Modular Software Example of Controller Inner-Loops Altitude Correction Example of Circular Arc Approximation Example of Waypoint Tracking Example Mission HUD and Flight Tracker

4 - Acknowledgements We d like to thank our faculty advisors, Professor Jon How and Col. Peter Young, for their guidance and support. We d also like to thank our academic sponsors, the MIT Department of Aeronautics and Astronautics, the MIT Department of Mechanical Engineering, the MIT Department of Electrical Engineering and Computer Science, and especially the MIT Edgerton Center. Finally, we d like to thank our corporate sponsors, Altium for their fantastic printed circuity board design software, NovAtel for their GPS equipment, and Microsoft for their development software. Thanks to all of our other sponsors as well: AME Manufacturing, EHKA&A, the Mathworks, Advanced Circuits, Geneva Aerospace, FreeWave Technologies, Phytec, Microchip Technologies, Analog Devices, PCB Express, and MicroStrain. Thank you!

5 1 Introduction Project AARES (Autonomous Aerial Reconnaissance Exploration System) is an interdisciplinary team of MIT undergraduate students with the shared aspiration of developing a fully-autonomous modular Unmanned Aircraft from the ground-up. These students, representing Aerospace, Electrical, and Mechanical Engineering, combine their diverse backgrounds and collective knowledge to solve difficult problems and develop innovative solutions. As UAVs see more use in increasingly diverse roles, their functions and capabilities must change as rapidly as their requirements. To develop innovative unmanned aircraft in minimal time and at minimal cost, we must have the ability not only to rapidprototype airframes; we must integrate complex avionics systems, control architectures, and ground station support equipment as well. To do this, standard ready-to-use components must be developed just as software can be rapidly composed from ready-to-use libraries. Given the wide range of real-world tasks assigned to UAVs today, we believe that flexibility and modularity are some of the most important factors in modern UAV design. There are no black boxes aboard our aircraft. Avionics hardware and software were designed by students using rapid-prototyping concepts, and autopilot and autonomy systems were designed and implemented from the ground-up. This journal paper gives an overview of the entire AARES project including design, implementation, testing, and safety. 2 Design Overview A modified NorthEast Sailplanes Viking was chosen as the airframe for the AUVSI competition. The aircraft is a small (4.5 ft. wingspan), electric-propulsion platform that is low-maintenance, lightweight, and extremely portable. In previous years, a larger gaspowered airframe was used but was found to be cumbersome to transport and difficult to service. The smaller Viking has adequate payload capabilities and excellent stability characteristics, making it ideal for our purposes. Custom avionics boards were designed entirely by students. The custom design of each board and modular architecture of the entire avionics system makes the aircraft flexible, upgradeable, and able to take on a wide range of tasks. The avionics were designed for rapid prototyping, giving us the ability to quickly design and upgrade the aircraft to meet changing mission and design requirements. 1

6 Aircraft dynamics were modeled mathematically using a variety of computational fluid dynamics tools. Wing and fuselage geometry and centers of mass were measured and used as parameters for computational fluid dynamics (CFD) software. A 3D model of the aircraft was created and imported into Athena Vortex Lattice (AVL), which was used to compute aerodynamics coefficients and stability derivatives. These were then used to model aircraft dynamics in Simulink using the Aerosim Blockset. This simulation provided a basis for the design of the control system. Controllers were designed from the ground-up with inner-loops controlling low-level functions such as pitch and roll and outer-loops controlling high-level functions such as heading and altitude. With the flexibility to choose a robust guidance platform, a unique nonlinear guidance controller was adapted from previous research. 1 The algorithm is efficient and tailored for this mission specifically, with the ability to dynamically change mission objectives mid-flight and follow new waypoints on-the-fly. A hardware-in-the-loop simulation was used to test and debug the control systems and guidance algorithms, minimizing the risk of in-flight failure. A ground station server computer handles all communication with the aircraft. The server then broadcasts state information (such as telemetry) via a TCP/IP network to peripheral ground station computers. These peripheral computers manage specific aspects of the mission and include a HUD/Telemetry Computer, a Mission Management Computer, and a Payload Computer. These three stations have the ability to send commands to the aircraft, but must do so through the server. The Flight Manager oversees all flight operations while three other team members man the peripheral computers and report directly to the Flight Manager. The aircraft was designed with safety as a top priority. The R/C receiver module has an integrated safety override should the autopilot fail, returning manual control to the pilot. If all radio communication is lost, the module commands a hard-over spin per competition regulations. Power systems are kept separated to lessen the probability of a system-wide power loss. Extensive measures have been taken to minimize RFI complications including wire shielding, RFI enclosures for high-risk boards, and strategic hardware placement. 3 Airframe While the competition does not have any specific requirements for the aircraft itself, the team made their own criteria to aid in airframe selection. From last year s experience, the team knew they needed a smaller, more manageable aircraft. However, it still 1 Park, S (2004) Avionics and Control System Development for Mid-Air Rendezvous of Two Unmanned Aerial Vehicles. PhD thesis. Massachusetts Institute of Technology. 2

7 needed to be able to carry up to 3 pounds of payload. To avoid the hassle of gasoline or glow engines, the team opted for an 4.5 ft. wingspan plane with an electric propulsion system. Its small size and electric propulsion would enable the aircraft to have its initial flight tests held on campus, rather than transporting everything to a distant airfield. Autopilot testing is done entirely at remote airfield locations due to safety concerns. The team chose the North East Sailplanes Viking (airframe shown in Figure 1). It met all of team s specifications with its light weight, low wing loading, easy handling, and electric power plant. The team built the aircraft stock, with only a few modifications to integrate the avionics. Initial flight testing proved that Figure 1: Photograph of airframe it was capable of handling 3 pounds of payload with minimal impact on flight characteristics. With the aircraft fully loaded, the 4200 mah lithium polymer battery pack and MP Jet 2810 brushless outrunner motor can deliver over 30 minutes of flight time. 4 Avionics 4.1 Requirements An avionics system designed for rapid prototyping must be able to measure the aircraft s state, act on its state, communicate with users on the ground, execute control algorithms, and be able to control a payload in order to complete a specific mission. In addition to the functions that the system must perform, there are several other design requirements which must be addressed if this system is to be successful. The system must expandable, in order to accommodate future needs that are yet unknown. New components must be easily added without altering previous hardware. The system must be fault tolerant because an aircraft in flight can be a dangerous situation. The propagation of errors must be controlled in a way that allows low-level failures to be masked and handled appropriately whenever possible. The failure of a non-essential sensor must not affect the ability of someone to fly the aircraft. The system must also be reconfigurable. If one component of the system needs to be changed, that change must not have global consequences which affect other aspects of the system. Finally, the system must exhibit managed complexity. If the avionics for an experimental aircraft are to be quickly setup, they must be reasonably easy to use and not overly complex. 3

8 4.2 Rapid Prototyping of Avionics If we are to develop innovative unmanned aircraft in minimal time, we must have the ability to rapidly build complex avionics systems from standard ready-to-use components just as software can be rapidly built from ready-to-use libraries. If these avionics systems are to be of use in these next generation aircraft, they must be extendable, reconfigurable, fault tolerant, and must exhibit managed complexity. To make this vision possible, several steps must be taken: 1. A power and communication standard must be developed which each module must adhere to. 2. Modular hardware must be designed to perform many of the core functions that are necessary for unmanned aircraft. Modules used on the aircraft are described in detail below. 3. Modular software must be developed that connect the hardware modules together and allow them to communicate with each other. 4. Module specific software must be written to enable each module to perform its specific functions. 5. Each module must be tested individually to ensure that it works according to specifications. 6. The modules should be integrated on an aircraft and flown in order to demonstrate their effectiveness. Many flight tests have been performed which demonstrated the operation of the modules on the aircraft. 4.3 General Architecture In order to meet the proposed design goals, the architecture of the avionics system is entirely modular. Each module is designed for a specific task and either measures some quantity, controls some device, communicates with the ground, or processes control algorithms. Additionally, a payload, such as a camera, can be controlled to complete mission requirements. Power is distributed to each module from the Power Module connected to the bus. This module monitors the batteries and regulates voltages. All communication between modules is done using the Controller Area Network (CAN) bus. This bus has come to dominate the automotive industry because of its fault-tolerant, noise tolerant, high bandwidth, event-driven architecture. Unlike Ethernet, the CAN bus is deterministic with nondestructive bus arbitration. 4

9 Communication on the bus is divided into two types of messages: broadcasts and commands. Commands can be sent to a specific module in order to control it. Broadcasts are sent from a module to every module on the bus. This allows for every module to have access to data which may be relevant to its operation. For example, a gimbaled video camera can be programmed to automatically adjust to the aircraft s pitch and roll without interference from the flight computer by accepting broadcasts from the Inertial Measurement Unit directly. More importantly, this design allows for the RF Transceiver to have access to all of the measured quantities on the aircraft. The RF Transceiver can then be programmed to stream telemetry data to the ground regardless of the state of the Flight Computer. If the Flight Computer were to fail or was not present at all, users on the ground could still have access to the aircraft s telemetry and use that information to make a safe manual landing. In operation, the flight computer initializes devices. Sensors broadcast their information on the bus. The flight computer uses the sensor information to execute flight control algorithms and then sends commands to actuators in order to control the aircraft. All the while, the RF modem is also receiving broadcasts and is able to transmit telemetry to the ground even in the absence of the flight computer. If a user desires to gain manual control of the aircraft, the RC receiver (being controlled by an RC transmitter on the ground) can send command packets directly to the actuators. This allows for manual control of the aircraft should anything go wrong. Control of the payload from the ground is also possible. A block diagram of the entire system is shown in Appendix A. 4.4 Modular Hardware Each hardware module is a union of general and specialized components. General components are common to nearly all of the avionics modules and allow for each module to interface with the avionics bus, display its status, and be programmed with custom software. In addition to the general components that define the universal capabilities of the system, specialized components exist that define the unique capabilities of an individual module. This specialized hardware often consists of a commercial off-the-shelf (COTS) component such as the Xtend radio modem or 3DM-GX1 inertial sensor. Other custom hardware typically exists to interface this COTS hardware with the microcontroller. On other boards such as the air data board, nearly all of the hardware is custom. 5

10 4.4.1 Power Module The Power Module is responsible for regulating and distributing power as well as monitoring battery status and current consumption. This power module is designed for use in an electric powered aircraft and has connections to two batteries. The primary battery powers all of the avionics and is designed to be either a 3-cell lithium ion battery or a 9-cell NiMH battery. The second battery is for powering the aircraft s electric motor and can be various sizes. The voltage and current draw can be measured from both batteries. Both the avionics and propulsion power systems can be turned on and off with using two switches. Additionally, the avionics can be powered from a ground power source which can be connected to this module. This connection can provide tethered power to the avionics when the plane is on the ground in order to minimize the drain on the main avionics battery and ensure maximum flight time. This ground connection also extends to the CAN bus to an external PC which can be used for debugging or ground testing Inertial Measurement Unit The Inertial Measurement Unit is responsible for measuring the attitude and change in attitude of the aircraft. The 3DM-GX1 was selected as the inertial sensor (IMU) to use for this module because of its integrated filtering, small size, and low power consumption. This device is capable of reporting its orientation at 75Hz over a simple RS-232 connection. It is also capable of measuring the lateral and vertical accelerations felt by the aircraft RF Transceiver When designing the RF Transceiver module, reliability and size were the most important considerations. The 900 MHz Xtend radio modem from MaxStream was selected as the COTS component of this module. This device is a frequency hopping spread spectrum modem capable of communicating over a range of several miles with error correction and packet acknowledgement. An LED is included on this module to indicate when the modem is transmitting and receiving. An integrated circuit provides power consumption monitoring, as the modem can use nearly 4 Figure 2: RF Transceiver watts of power from the 5.0 volt power supply. Finally, a temperature sensor in included to ensure the module does not over heat. 6

11 4.4.4 GPS Receiver Module The GPS Receiver Module is responsible for measuring the position and true velocity of the aircraft. Using a NovAtel Superstar II, this module is able to obtain these measurements at 5Hz with a position error of as little as +/- 1 meter and velocity error of +/ meters per second. The Superstar II is a 12 channel receiver capable of carrier phase tracking. It can make use of both differential and WAAS corrections and reports its accuracy in real time RC Receiver The RC Receiver Module is responsible for receiving the radio frequency signal from a standard RC transmitter and measuring the pulse widths that are transmitted. The processor is able to measure the pulse widths that are decoded by the Electron 6 RC receiver Air Data Module The Air Data Module is responsible for measuring the aircraft s altitude and airspeed using pressures from the aircraft s Pitot tube. The Pitot tube delivers static and dynamic pressures which are measured using sensors P1 and P2. By decreasing the range of the sensor to 0-5,000 ft above sea level, the module should have a resolution of 0.07 feet. Additionally, the connection for an external temperature sensor is present in case the air temperature is needed in calculations. Figure 3: RC Receiver Figure 4: Air Data Module Quad Actuator The Quad Servo Controller (or Quad Actuator) is designed to control four standard RC servos. Several of these modules can be connected to the bus if more than four servos need to be controlled. Each servo is controlled by varying the length of a digital pulse that is sent to the servo at 50Hz. This module allows for the pulse width to each servo to vary between 500us and 2500us with a resolution of less than 1us. Figure 5: Quad Actuator 7

12 4.5 Modular Software As each module contains a set of common hardware components, it is desirable to also write both common and specific software for each hardware module. As indicated in the graphic to the right, modules contain a block of Core Software with core Interface Modules that handle low level functionality including CAN connectivity, status LED control, and system timing. The Core Software handles basic functionality including resetting the device and changing the device s operation mode. Another layer is built upon this low-level and mid-level core software which is specific to each hardware module. This software includes both low-level custom Interface Modules and high-level Board Specific Software. This organization of embedded code is beneficial for several reasons. First, if a feature is to be added to the system such that it will be used on all hardware modules, that feature needs only to be added in the core software which will be loaded onto all hardware modules. Second, when writing software for a new module, a large portion of the code from previous modules is easily reused as it is present in the Core Software. Third, when changes need Figure 6: Modular Software to be made during testing, these changes can generally be made in one place as they are either specific to a single board or included in the Core Software which is common to all boards. 4.6 Testing Individual Board Testing Each board is tested by powering the module and connecting it to a PC using a CANto-USB converter. This enables the PC to receive and send CAN packets to the avionics hardware. Custom programs written in visual basic are able to display data from the avionics modules and allow for interaction with the module Networked Ground Testing When several modules have passed the individual board testing, they are connected together on the ground to ensure that they do not interfere with each other and can operate collectively. During this testing, there were several problems with radio frequency interference (RFI). These problems were solved using wire shielding and RFI enclosures, and by changing the orientation of hardware modules. 8

13 4.6.3 Flight Testing When modules had been proven to work together collectively without interference, they were installed on the aircraft. The aircraft was able to stream telemetry information to the ground using the RF Transceiver. On the ground, this information was received using an Xtend RF modem connected to a laptop s serial power. This serial information was displayed in the Heads Up Display (HUD) in order to demonstrate the functionality of the RF Transceiver, IMU, Power Module, and GPS in flight. 5 Controls 5.1 Modeling One of the first steps to modeling our airplane was to measure the various quantities that determine the dynamics and stability of the airplane. Quantities that had to be measured were the dimensions of the airplane, the airfoil shape, control surface deflections, the mass, and the moments of inertia about the three axes of the airplane. All geometry measurements were referenced with respect to the propeller nut, with the x- axis pointing from the reference point to the front of the horizontal stabilizer, the y-axis towards the right wing, and the z-axis up. The sizes of the various airplane components were measured, as well as their position with respect to the reference point. The control surface deflections were also measured with a ruler, and then the angles computed trigonometrically. The wing s airfoil was determined by measuring the maximum camber, maximum camber location, and the maximum thickness and approximating the airfoil as a NACA 4-digit airfoil. Moment of inertia measurements were important to establish the correct dynamics of the airplane. Although not all payload was available, a representative payload was placed in the airframe to correctly simulate the mass distribution of the airplane. To measure the moment of inertia about the x-axis, the airplane was hung vertically from a spring with the x-axis pointing directly down. The airplane was then turned approximately 30 degrees about the vertical axis, and allowed to rotate back and forth. The moment of inertia was determined using the relationship between the spring s rotational spring constant and the period of rotation. This technique was repeated for the other two axes. The mass of the airplane was determined by individually weighing the airplane and the various components that would be making up the payload. The next step after all quantities had been measured was to build a virtual model of the 9

14 airplane. The program Athena Vortex Lattice (AVL) was chosen for this task. AVL is a 3-dimensional aerodynamics analysis program that provides the forces on the airplane and their coefficients as well as stability derivatives. The airplane s operating parameters and the control surface deflections can be changed to simulate the aircraft under different flight conditions in the linear flight regime. The information that AVL provided about the aircraft was essential for a complete characterization of the aircraft about our intended operating point. 5.2 Numerical Simulation The MATLAB Simulink toolbox was used to create a real-time simulation of the aircraft for controller development and hardware-in-the-loop simulation. Instead of building a dynamics model of the aircraft from scratch, Dynamics Unlimited s AeroSim Blockset was utilized as a baseline. It was modified with the stability derivatives, mass properties, and aerodynamic coefficients found from modeling the aircraft in AVL. To verify that the simulation was realistic, vehicle visualization was performed using FlightGear, an open-source flight simulator. The team s pilots then flew the dynamics model as a standard R/C simulator, comparing the handling characteristics of the simulation with the actual aircraft. They found that it flew very much like the actual aircraft after adjusting a couple of stability derivatives. The finished Simulink model allowed for development of the control architecture in parallel with that of the flight electronics. 5.3 Controller Design The low-level controllers are designed to stabilize and control the aircraft s altitude, airspeed, and heading. This control layer is then commanded by upper-level navigation algorithms. The low-level controllers are based on an independent nested PID control loop layout. Nested PID compensators were chosen for their robust performance and straight-forward gain tuning. They also allow the user (human or upper-level controllers) to directly command different aircraft states than initially decided if desired, such as turn rate or bank angle instead of heading. Also, the actual aircraft dynamics are masked for the upper level controllers by layering the control loops. The upper level controllers see the dynamics of the lower level controllers, which can be controlled by the designer. This allows for higher performance with relatively low complexity. The innermost controllers perform the most basic functions, including commanding roll and pitch angle, to stabilize the aircraft. An altitude controller was designed and tuned to the dynamics of the pitch angle controller it commands. Likewise, a turn rate controller commands a bank angle to the bank angle controller. To command a desired 10

15 heading, a third layer is added, which outputs turn rate commands to achieve that heading. Figure 7: Example of Controller Inner-Loops The controllers were designed and tuned from the inner-most outward. This is necessary because the inner controller dynamics determine the tuning of the outer compensators. Gains were initially set using the Ziegler-Nichols closed-loop tuning method. Once these were found, they were manually tuned for a fast response with acceptable levels of overshoot and steady-state tracking. Once set, the overlaying compensator is tuned the same way. While each command path may contain more than one controller, each path is independent of the others, and is treated as a single-input, single-output system. While this is not the ideal control architecture, it fits well into the managed modularity with low complexity theme of the entire system. It takes advantage of the fact that the aircraft being used has only a small amount of axis coupling. Any change in state by an outside controller is seen as a disturbance by the compensator of that state. This can most easily be seen during a turn. As the aircraft is banked, it will start to lose altitude if the elevator trim is not changed. A human pilot knows this and corrects for it during the turn by applying up elevator as he or she banks the aircraft. In this control architecture, a heading change command only directly affects the controllers in that control path; the pitch control path is ignored. However, as soon as the aircraft starts to bank and loses altitude, the altitude controller sees the change as a disturbance and compensates for it, just as it would react to a wind gust or thermal. To determine how well this architecture performs, a simulation was set up with an 180 commanded turn while commanding constant altitude. As can be seen from Figure 9, the altitude controller reacted to the initial loss of altitude nearly immediately with only 2 meters of deviation. A second simulation was run with the pitch controller turned off, holding the elevator 11

16 trim, which can be seen in red. This resulted in a 70 meter loss of altitude, demonstrating the effectiveness of the independent control architecture. Figure 8: Altitude Correction 5.4 Final Controller Architecture Block diagrams of the final controller architecture are shown in Appendix B. 5.5 Discretization and Code Generation As described above, the control architecture was designed and tested in a continuous (non-discrete) context. In order to implement the controllers on a flight computer, the transfer functions were discretized. While this could have been done by hand using a simple Tustin transformation into the discrete Z-domain, Simulink s Model Discretizer was used. This tool performs an identical Tustin transformation, and allows for an inherited time step (sample rate) which adds flexibility in setting the hardware sample rate(s). After the various control blocks were discretized, MATLAB was again used to generate C-code for the entire control architecture. Again, the code could have been written by 12

17 hand by converting the discrete transfer functions into algebraic difference equations. However, given the probability of error and the intricacy of the inner-outer loop setup, the code generator saved a huge amount of coding and debugging time. Code was then simply copied to the flight computer with minimal modification to setup communication with the sensors and actuators. A hardware-in-the-loop simulation was used to verify and tune the discrete computer control architecture (see Autonomy ). 6 Autonomy To complete a mission the AARES autonomy module must provide three functions: 1. Control of basic aircraft stability 2. Flight path tracking 3. Mission plan execution, including dynamic task assignment These capabilities are provided by a low level closed-loop control system (described above), a high level navigation algorithm, and a mission executive based on a series of commands called air task orders. Like most components of AARES, each part of the autonomy module is a custom component created by students. 6.1 Navigation Algorithm With the flexibility to choose a robust guidance platform, the AARES team implemented a unique nonlinear guidance controller. In contrast to traditional path following methods, the controller does not use cross track error to drive the aircraft toward the desired flight path. Instead, the controller searches the path for a point that is a fixed distance away from the aircraft, forming an instantaneous tracking point for the trajectory. To generate a control command, the flight path between the current position and the target position is approximated by a circular arc (Figure 10). Using this arc and the current velocity, a desired lateral acceleration is calculated and actuated with a simple low level roll command. Once the aircraft gets close enough to the end of the segment that it cannot track the segment anymore, the aircraft begins tracking the segment between the next two waypoints (Figure 11). The result is a trajectory which naturally converges with the desired flight path and anticipates discrete changes in the path s direction with smooth turns. 6.2 Mission Execution To provide commands for navigation and low level control, a command structure was created called an air task order. Air task orders are created by stringing together 13

18 Figure 9: Example of Circular Arc Approximation Figure 10: Example of Waypoint Tracking two components: waypoints and segments. Segments describe the movement between two points, and waypoints define the actions to be performed at these points. In general, waypoints are designated as navigation waypoints, which define the general shape of the desired flight path and are not absolutely vital to mission success. When a waypoint is critical to the flight plan it is designated as a mission waypoint. If a mission waypoint is missed, the aircraft will execute a pre-defined contingency operation as described in the next section. Several pre-defined actions can be appended to waypoints to simplify common mission tasks such as loitering, changing altitude in a fixed location, or taking a picture. For more complex operations, an air task order is created to provide a sequence of commands to the navigation and control software (Figure 12). To create a mission, several air task orders are uploaded to the flight computer to be executed in series. The Figure 11: Example Mission air task order structure also allows for dynamic re-tasking. The ground station operators can insert a waypoint or entire flight plan into the original mission sequence during the flight by simply uploading a new air task order. 6.3 Contingency Operations During any flight, the autonomy software will continually monitor the status of the RF communication link and the progress of the current air task order. In the event of an 14

19 anomaly, the software will execute pre-defined air task orders that are uploaded at the start of the mission. For example, an RF modem signal loss will result in the aircraft heading to a pre-defined home position. The RC link and RF modem are also independently monitored by the RcMUX board, which will independently execute a hard over if all control is lost. 6.4 Hardware-in-the-Loop Simulator To provide a realistic environment for developing flight software, the AARES avionics system is capable of entering a special Hardware In the Loop (HIL) simulation mode. In HIL mode, onboard sensor modules are disabled and an external simulator is directly connected to the avionics bus. The simulator, which utilizes the same flight model used for initial controls prototyping, replicates the messages sent by all onboard sensor systems and broadcasts them to the avionics bus. This architecture requires no special modifications to the flight computer software, allowing the flight computer to operate exactly as it would in a real flight. The RF communication link also remains unaffected, providing the capability for a complete mission simulation from ground station software. 7 Ground Control Station The ground control station (GCS) features a highly modular architecture. It is composed of four major components. The server receives data from the RF link and passes it to the heads up display (HUD), mission management (MM), and payload clients. One advantage of the GCS s server/client architecture is that it allows communication with the plane to be abstracted away from the controls on the ground. The GCS s modularity also allows its individual components to be designed, implemented, and tested independently of the others. In addition, it precludes individual errors from propagating and causing the entire system to fail. Together, the server s three major clients provide all the ground control and observation capability required to accomplish the mission. After receiving the RF packets in CAN format, the server parses them and updates its copy of the aircraft state with the new data. In parallel, the server also converts the current state into an extensible markup language (XML) schema and transmits it over TCP/IP to the other nodes. XML was chosen because its parsers are simple to write in a wide variety of languages: thus, the choice of language at each node is neatly abstracted away. The three clients (HUD, MM, and payload) receive the state information and, optionally, send commands back to the server (in XML as well) to be relayed to the aircraft s flight computer. 15

20 The HUD shows the current state of the aircraft and allows manual joystick control. Specifically, it shows the aircraft s altitude, pitch, roll, heading in a flight simulatorlike interface. It also shows battery life indicators for the motor batteries and avionics batteries, and RF signal strength. A top-down view of the aircraft on a map of the area is displayed. Simply by clicking a button, the user can override the aircraft s autopilot and take manual control. Through the HUD, the aircraft can be controlled with a joystick or through higher-level commands, such as change heading, or hold altitude. First, a flight plan, consisting of air task orders, is created with the MM software. To create the flight plan, the user first loads a satellite image of the terrain into the program. Then, onto this map image air task orders are created and appended together. In each air task order, the user can place a runway, mission waypoints, navigational waypoints, and other points of interest. The runway is the point at which the aircraft takes off and lands. Mission waypoints are mission-critical, and may not be missed. Navigational waypoints are placed to aid the flight computer in finding a path between mission waypoints; thus, they can Figure 13: HUD and Flight Tracker be skipped if necessary. For both types of waypoint, target velocity, altitude and tolerance can be set. All of these attributes along with corresponding points and a map are saved as air task orders, and any combination of air task orders with take-off and land operations can constitute a flight plan and be sent to the flight computer. Then, while the mission is underway, the map shows in real time aircraft s position in relation to the map and targets, and its progress toward completing the ATO. Finally, the payload node handles mission-specific duties. For the AUVSI competition, the still camera s photos are downloaded to the payload node and entered into the software. This software generates Keyhole markup language (KML) that associates the still images with their location and perspective on the ground. Google Earth then reads the KML and overlays the still images onto the map. In order to manage all the components of the GCS effectively, a single user (the GCS operator ) is the primary point of contact during the mission. While other users can 16

21 help identify problems and troubleshoot, the GCS operator is responsible for relaying mission status to the other members of the team. If significant problems arise, the GCS operator will first attempt to take manual control of the aircraft with the HUD node. In the case of an emergency, this user will delegate control to an experienced RC pilot who will override the flight computer and safely land the plane. Together, the components of the GCS are a highly-modular approach to aircraft ground support, allowing rapid response to ever-changing mission requirements. 8 Safety When developing and operating UAVs, safety is of utmost importance. Throughout the development of the team-designed autopilot, every possible precaution was taken to ensure safe operation. 8.1 Safety Override The autopilot is integrated in parallel with a standard R/C receiver. Servo commands from the R/C receiver and autopilot are sent to a safety switch, which then selects which device controls the servos. Channel 5 from the R/C receiver is connected to the Master input of the safety switch. This assures that control can be turned over to R/C control in the case of any type of autopilot loss. It also gives the pilot complete authority to override the autopilot whenever he or she deems necessary without any action needed from the ground station or flight computer. The safety switch setup assures that control of the vehicle is maintained in the event of autopilot failure. AUVSI rules state that the aircraft is to execute a hard-over spin in the case that manual control is lost. This is accomplished using a PCM R/C receiver that is programmed to select manual control and command the servos to their hard-over positions if the transmitter signal is lost. 8.2 Power Systems These safety measures only work as long as the power system on the aircraft is functioning. To minimize the chances of a power failure, the autopilot and backup R/C systems have independent power circuits. All the voltages and currents are monitored on the ground for any problems. The servos are powered as a part of the backup R/C system, so control of the aircraft is maintained in the event of total autopilot power failure. 17

22 8.3 RFI Protection Radio frequency interference proved to be a problem during the initial testing phases. RFI from the switching power supply, GPS board, and unshielded cables weakened the R/C link among other things. This was accounted for by using RFI enclosures for avionics boards as necessary, shielding and winding all cables within the fuselage, and strategically placing hardware and antennas such that RFI was minimized. 9 Conclusion As UAVs see more use in increasingly diverse roles, their functions and capabilities must change as rapidly as their requirements. The Project AARES UAV was designed specifically with this in mind. The aircraft s suite of custom, modular components make it easily adaptable to a wide range of missions. This design lends itself to the rapid development of avionics, control architecture, and ground station support equipment, and the AUVSI competition has given the team an opportunity to exercise these techniques. The result is a UAV that is highly-customized, designed from the ground-up by students, and ready to take on the challenges that the competition has to offer. 18

23 Appendix A - Full System Block Diagram Flight Computer GPS Receiver Power Module Li-Ion Li-Polymer ESC Servo Power Brushless Motor Air Data Module IMU CAN Bus RC Safety Override Servo Servo Servo Servo Sonar Altimeter Prism Servo RF Transceiver Video Transmitter PCM Receiver 900 MHz Ground Power HIL Sim Plane Ground 2.4 GHz 72 MHz RF Transceiver CAN GCS Server Video Receiver RC Transmitter TCP/IP USB Backup Pilot HUD Diagnostics Mission Management Payload / Imaging HUD Operator Safety Officer Mission Manager

24 Appendix B - Overall Control Architecture Stability Control Architecture

Classical Control Based Autopilot Design Using PC/104

Classical Control Based Autopilot Design Using PC/104 Classical Control Based Autopilot Design Using PC/104 Mohammed A. Elsadig, Alneelain University, Dr. Mohammed A. Hussien, Alneelain University. Abstract Many recent papers have been written in unmanned

More information

University of Minnesota. Department of Aerospace Engineering & Mechanics. UAV Research Group

University of Minnesota. Department of Aerospace Engineering & Mechanics. UAV Research Group University of Minnesota Department of Aerospace Engineering & Mechanics UAV Research Group Paw Yew Chai March 23, 2009 CONTENTS Contents 1 Background 3 1.1 Research Area............................. 3

More information

FLCS V2.1. AHRS, Autopilot, Gyro Stabilized Gimbals Control, Ground Control Station

FLCS V2.1. AHRS, Autopilot, Gyro Stabilized Gimbals Control, Ground Control Station AHRS, Autopilot, Gyro Stabilized Gimbals Control, Ground Control Station The platform provides a high performance basis for electromechanical system control. Originally designed for autonomous aerial vehicle

More information

Heterogeneous Control of Small Size Unmanned Aerial Vehicles

Heterogeneous Control of Small Size Unmanned Aerial Vehicles Magyar Kutatók 10. Nemzetközi Szimpóziuma 10 th International Symposium of Hungarian Researchers on Computational Intelligence and Informatics Heterogeneous Control of Small Size Unmanned Aerial Vehicles

More information

GPS System Design and Control Modeling. Chua Shyan Jin, Ronald. Assoc. Prof Gerard Leng. Aeronautical Engineering Group, NUS

GPS System Design and Control Modeling. Chua Shyan Jin, Ronald. Assoc. Prof Gerard Leng. Aeronautical Engineering Group, NUS GPS System Design and Control Modeling Chua Shyan Jin, Ronald Assoc. Prof Gerard Leng Aeronautical Engineering Group, NUS Abstract A GPS system for the autonomous navigation and surveillance of an airship

More information

Hardware in the Loop Simulation for Unmanned Aerial Vehicles

Hardware in the Loop Simulation for Unmanned Aerial Vehicles NATIONAL 1 AEROSPACE LABORATORIES BANGALORE-560 017 INDIA CSIR-NAL Hardware in the Loop Simulation for Unmanned Aerial Vehicles Shikha Jain Kamali C Scientist, Flight Mechanics and Control Division National

More information

Implementation of Nonlinear Reconfigurable Controllers for Autonomous Unmanned Vehicles

Implementation of Nonlinear Reconfigurable Controllers for Autonomous Unmanned Vehicles Implementation of Nonlinear Reconfigurable Controllers for Autonomous Unmanned Vehicles Dere Schmitz Vijayaumar Janardhan S. N. Balarishnan Department of Mechanical and Aerospace engineering and Engineering

More information

New functions and changes summary

New functions and changes summary New functions and changes summary A comparison of PitLab & Zbig FPV System versions 2.50 and 2.40 Table of Contents New features...2 OSD and autopilot...2 Navigation modes...2 Routes...2 Takeoff...2 Automatic

More information

Design of a Flight Stabilizer System and Automatic Control Using HIL Test Platform

Design of a Flight Stabilizer System and Automatic Control Using HIL Test Platform Design of a Flight Stabilizer System and Automatic Control Using HIL Test Platform Şeyma Akyürek, Gizem Sezin Özden, Emre Atlas, and Coşku Kasnakoğlu Electrical & Electronics Engineering, TOBB University

More information

Hardware Modeling and Machining for UAV- Based Wideband Radar

Hardware Modeling and Machining for UAV- Based Wideband Radar Hardware Modeling and Machining for UAV- Based Wideband Radar By Ryan Tubbs Abstract The Center for Remote Sensing of Ice Sheets (CReSIS) at the University of Kansas is currently implementing wideband

More information

TEAM AERO-I TEAM AERO-I JOURNAL PAPER DELHI TECHNOLOGICAL UNIVERSITY Journal paper for IARC 2014

TEAM AERO-I TEAM AERO-I JOURNAL PAPER DELHI TECHNOLOGICAL UNIVERSITY Journal paper for IARC 2014 TEAM AERO-I TEAM AERO-I JOURNAL PAPER DELHI TECHNOLOGICAL UNIVERSITY DELHI TECHNOLOGICAL UNIVERSITY Journal paper for IARC 2014 2014 IARC ABSTRACT The paper gives prominence to the technical details of

More information

Recent Progress in the Development of On-Board Electronics for Micro Air Vehicles

Recent Progress in the Development of On-Board Electronics for Micro Air Vehicles Recent Progress in the Development of On-Board Electronics for Micro Air Vehicles Jason Plew Jason Grzywna M. C. Nechyba Jason@mil.ufl.edu number9@mil.ufl.edu Nechyba@mil.ufl.edu Machine Intelligence Lab

More information

VCU Skyline. Team Members: Project Advisor: Dr. Robert Klenke. Last Modified May 13, 2004 VCU SKYLINE 1

VCU Skyline. Team Members: Project Advisor: Dr. Robert Klenke. Last Modified May 13, 2004 VCU SKYLINE 1 VCU Skyline Last Modified May 13, 2004 Team Members: Abhishek Handa Kevin Van Brittiany Wynne Jeffrey E. Quiñones Project Advisor: Dr. Robert Klenke VCU SKYLINE 1 * Table of Contents I. Abstract... 3 II.

More information

IPRO 312: Unmanned Aerial Systems

IPRO 312: Unmanned Aerial Systems IPRO 312: Unmanned Aerial Systems Kay, Vlad, Akshay, Chris, Andrew, Sebastian, Anurag, Ani, Ivo, Roger Dr. Vural Diverse IPRO Group ECE MMAE BME ARCH CS Outline Background Approach Team Research Integration

More information

Design of a Remote-Cockpit for small Aerospace Vehicles

Design of a Remote-Cockpit for small Aerospace Vehicles Design of a Remote-Cockpit for small Aerospace Vehicles Muhammad Faisal, Atheel Redah, Sergio Montenegro Universität Würzburg Informatik VIII, Josef-Martin Weg 52, 97074 Würzburg, Germany Phone: +49 30

More information

2007 AUVSI Competition Paper Near Space Unmanned Aerial Vehicle (NSUAV) Of

2007 AUVSI Competition Paper Near Space Unmanned Aerial Vehicle (NSUAV) Of 1 2007 AUVSI Competition Paper Near Space Unmanned Aerial Vehicle (NSUAV) Of University of Colorado at Colorado Springs (UCCS) Plane in flight June 9, 2007 Faculty Advisor: Dr. David Schmidt Team Members:

More information

THE DEVELOPMENT OF A LOW-COST NAVIGATION SYSTEM USING GPS/RDS TECHNOLOGY

THE DEVELOPMENT OF A LOW-COST NAVIGATION SYSTEM USING GPS/RDS TECHNOLOGY ICAS 2 CONGRESS THE DEVELOPMENT OF A LOW-COST NAVIGATION SYSTEM USING /RDS TECHNOLOGY Yung-Ren Lin, Wen-Chi Lu, Ming-Hao Yang and Fei-Bin Hsiao Institute of Aeronautics and Astronautics, National Cheng

More information

The drone for precision agriculture

The drone for precision agriculture The drone for precision agriculture Reap the benefits of scouting crops from above If precision technology has driven the farming revolution of recent years, monitoring crops from the sky will drive the

More information

A Mini UAV for security environmental monitoring and surveillance: telemetry data analysis

A Mini UAV for security environmental monitoring and surveillance: telemetry data analysis A Mini UAV for security environmental monitoring and surveillance: telemetry data analysis G. Belloni 2,3, M. Feroli 3, A. Ficola 1, S. Pagnottelli 1,3, P. Valigi 2 1 Department of Electronic and Information

More information

Formation Flight CS 229 Project: Final Report

Formation Flight CS 229 Project: Final Report Formation Flight CS 229 Project: Final Report Zouhair Mahboubi Tao Wang December 11 th, 2009 Stanford University Abstract This paper is submitted as the requirement for the final project report for the

More information

Hardware-in-the-Loop Simulation for a Small Unmanned Aerial Vehicle A. Shawky *, A. Bayoumy Aly, A. Nashar, and M. Elsayed

Hardware-in-the-Loop Simulation for a Small Unmanned Aerial Vehicle A. Shawky *, A. Bayoumy Aly, A. Nashar, and M. Elsayed 16 th International Conference on AEROSPACE SCIENCES & AVIATION TECHNOLOGY, ASAT - 16 May 26-28, 2015, E-Mail: asat@mtc.edu.eg Military Technical College, Kobry Elkobbah, Cairo, Egypt Tel : +(202) 24025292

More information

Introducing the Quadrotor Flying Robot

Introducing the Quadrotor Flying Robot Introducing the Quadrotor Flying Robot Roy Brewer Organizer Philadelphia Robotics Meetup Group August 13, 2009 What is a Quadrotor? A vehicle having 4 rotors (propellers) at each end of a square cross

More information

OughtToPilot. Project Report of Submission PC128 to 2008 Propeller Design Contest. Jason Edelberg

OughtToPilot. Project Report of Submission PC128 to 2008 Propeller Design Contest. Jason Edelberg OughtToPilot Project Report of Submission PC128 to 2008 Propeller Design Contest Jason Edelberg Table of Contents Project Number.. 3 Project Description.. 4 Schematic 5 Source Code. Attached Separately

More information

Various levels of Simulation for Slybird MAV using Model Based Design

Various levels of Simulation for Slybird MAV using Model Based Design Various levels of Simulation for Slybird MAV using Model Based Design Kamali C Shikha Jain Vijeesh T Sujeendra MR Sharath R Motivation In order to design robust and reliable flight guidance and control

More information

U-Pilot can fly the aircraft using waypoint navigation, even when the GPS signal has been lost by using dead-reckoning navigation. Can also orbit arou

U-Pilot can fly the aircraft using waypoint navigation, even when the GPS signal has been lost by using dead-reckoning navigation. Can also orbit arou We offer a complete solution for a user that need to put a payload in a advanced position at low cost completely designed by the Spanish company Airelectronics. Using a standard computer, the user can

More information

A New Perspective to Altitude Acquire-and- Hold for Fixed Wing UAVs

A New Perspective to Altitude Acquire-and- Hold for Fixed Wing UAVs Student Research Paper Conference Vol-1, No-1, Aug 2014 A New Perspective to Altitude Acquire-and- Hold for Fixed Wing UAVs Mansoor Ahsan Avionics Department, CAE NUST Risalpur, Pakistan mahsan@cae.nust.edu.pk

More information

North Carolina State University. Aerial Robotics Club. Autonomous Reconnaissance System

North Carolina State University. Aerial Robotics Club. Autonomous Reconnaissance System North Carolina State University Aerial Robotics Club Autonomous Reconnaissance System Author: Dan Edwards Submitted: 2 July, 2005 Abstract This paper describes the North Carolina State University Aerial

More information

North Carolina State University Aerial Robotics Club

North Carolina State University Aerial Robotics Club North Carolina State University Aerial Robotics Club 2007 AUVSI Student UAS Competition Journal Paper Entry June 1, 2007 by Matthew Hazard (NCSU 08) with thanks to Alan Stewart and James Scoggins NCSU

More information

Post-Installation Checkout All GRT EFIS Models

Post-Installation Checkout All GRT EFIS Models GRT Autopilot Post-Installation Checkout All GRT EFIS Models April 2011 Grand Rapids Technologies, Inc. 3133 Madison Avenue SE Wyoming MI 49548 616-245-7700 www.grtavionics.com Intentionally Left Blank

More information

Featherweight GPS Tracker User s Manual June 16, 2017

Featherweight GPS Tracker User s Manual June 16, 2017 Featherweight GPS Tracker User s Manual June 16, 2017 Hardware Configuration and Installation The dimensions for the board are provided below, in inches. Note that with the antenna installed, the total

More information

Operating Handbook For FD PILOT SERIES AUTOPILOTS

Operating Handbook For FD PILOT SERIES AUTOPILOTS Operating Handbook For FD PILOT SERIES AUTOPILOTS TRUTRAK FLIGHT SYSTEMS 1500 S. Old Missouri Road Springdale, AR 72764 Ph. 479-751-0250 Fax 479-751-3397 Toll Free: 866-TRUTRAK 866-(878-8725) www.trutrakap.com

More information

The survey-grade mapping drone

The survey-grade mapping drone The survey-grade mapping drone 3 reasons to choose the ebee RTK 01. Survey-grade accuracy Absolute orthomosaic / Digital Elevation Model accuracy of down to 3 cm (1.2 in) without the need for GCPs meaning

More information

1 P a g e. P13231 UAV Test Bed Setup Manual

1 P a g e. P13231 UAV Test Bed Setup Manual 1 P a g e P13231 UAV Test Bed Setup Manual Table of Contents Introduction....3 Wings... 3-4 Pitot Tube....3 Aileron Fault...4 Accelerometers.4 Fuselage.. 5-8 GPS.5 FPV System..5 ArduPilot 7 GoPro 7 Rudder

More information

2009 Student UAS Competition. Abstract:

2009 Student UAS Competition. Abstract: UNIVERSITY OF PUERTO RICO MAYAGUEZ CAMPUS COLLEGE OF ENGINEERING 2009 Student UAS Competition Journal Paper Team Members: Pablo R. Mejías, Merqui Galarza Jeancarlo Colón Naldie Torres Josue Comulada Veronica

More information

Project Number: 13231

Project Number: 13231 Multidisciplinary Senior Design Conference Kate Gleason College of Engineering Rochester Institute of Technology Rochester, New York 14623 Project Number: 13231 UAV GROUND-STATION AND SEEDED FAULT DETECTION

More information

SMART BIRD TEAM UAS JOURNAL PAPER

SMART BIRD TEAM UAS JOURNAL PAPER SMART BIRD TEAM UAS JOURNAL PAPER 2010 AUVSI STUDENT COMPETITION MARYLAND ECOLE POLYTECHNIQUE DE MONTREAL Summary 1 Introduction... 4 2 Requirements of the competition... 4 3 System Design... 5 3.1 Design

More information

UAV Flight Control Using Flow Control Actuators

UAV Flight Control Using Flow Control Actuators AIAA Atmospheric Flight Mechanics Conference 08-11 August 2011, Portland, Oregon AIAA 2011-6450 UAV Flight Control Using Flow Control Actuators Eric N Johnson, Girish Chowdhary, Rajeev Chandramohan, Anthony

More information

Pitlab & Zbig FPV System Version 2.60a. Pitlab&Zbig OSD. New functions and changes in v2.60. New functions and changes since version 2.

Pitlab & Zbig FPV System Version 2.60a. Pitlab&Zbig OSD. New functions and changes in v2.60. New functions and changes since version 2. Pitlab & Zbig FPV System Version 2.60a since version 2.50a Pitlab&Zbig OSD in v2.60a Added support for new Pitlab airspeed sensor. Sensor is connected to yellow OSD socket and is configured in similar

More information

Digiflight II SERIES AUTOPILOTS

Digiflight II SERIES AUTOPILOTS Operating Handbook For Digiflight II SERIES AUTOPILOTS TRUTRAK FLIGHT SYSTEMS 1500 S. Old Missouri Road Springdale, AR 72764 Ph. 479-751-0250 Fax 479-751-3397 Toll Free: 866-TRUTRAK 866-(878-8725) www.trutrakap.com

More information

INSTRUCTIONS. 3DR Plane CONTENTS. Thank you for purchasing a 3DR Plane!

INSTRUCTIONS. 3DR Plane CONTENTS. Thank you for purchasing a 3DR Plane! DR Plane INSTRUCTIONS Thank you for purchasing a DR Plane! CONTENTS 1 1 Fuselage Right wing Left wing Horizontal stabilizer Vertical stabilizer Carbon fiber bar 1 1 1 7 8 10 11 1 Audio/video (AV) cable

More information

Jager UAVs to Locate GPS Interference

Jager UAVs to Locate GPS Interference JIFX 16-1 2-6 November 2015 Camp Roberts, CA Jager UAVs to Locate GPS Interference Stanford GPS Research Laboratory and the Stanford Intelligent Systems Lab Principal Investigator: Sherman Lo, PhD Area

More information

University of Alberta Aerial Robotics Group

University of Alberta Aerial Robotics Group University of Alberta Aerial Robotics Group 2008 AUVSI Student UAS Competition Journal Paper Submission May 28, 2008 Abstract. This paper describes the 2008 foray of the University of Alberta Aerial Robotics

More information

Testing Autonomous Hover Algorithms Using a Quad rotor Helicopter Test Bed

Testing Autonomous Hover Algorithms Using a Quad rotor Helicopter Test Bed Testing Autonomous Hover Algorithms Using a Quad rotor Helicopter Test Bed In conjunction with University of Washington Distributed Space Systems Lab Justin Palm Andy Bradford Andrew Nelson Milestone One

More information

Development of Hybrid Flight Simulator with Multi Degree-of-Freedom Robot

Development of Hybrid Flight Simulator with Multi Degree-of-Freedom Robot Development of Hybrid Flight Simulator with Multi Degree-of-Freedom Robot Kakizaki Kohei, Nakajima Ryota, Tsukabe Naoki Department of Aerospace Engineering Department of Mechanical System Design Engineering

More information

Experimental Cooperative Control of Fixed-Wing Unmanned Aerial Vehicles

Experimental Cooperative Control of Fixed-Wing Unmanned Aerial Vehicles Experimental Cooperative Control of Fixed-Wing Unmanned Aerial Vehicles Selcuk Bayraktar, Georgios E. Fainekos, and George J. Pappas GRASP Laboratory Departments of ESE and CIS University of Pennsylvania

More information

RC Altimeter #2 BASIC Altitude data recording and monitoring system 3/8/2009 Page 2 of 11

RC Altimeter #2 BASIC Altitude data recording and monitoring system 3/8/2009 Page 2 of 11 Introduction... 3 How it works... 3 Key features... 3 System requirements... 3 Hardware... 4 Specifications... 4 Using the RC Altimeter #2 BASIC module... 5 Powering the module... 5 Mounting the module...

More information

Engtek SubSea Systems

Engtek SubSea Systems Engtek SubSea Systems A Division of Engtek Manoeuvra Systems Pte Ltd SubSea Propulsion Technology AUV Propulsion and Maneuvering Modules Engtek SubSea Systems A Division of Engtek Manoeuvra Systems Pte

More information

Digiflight II SERIES AUTOPILOTS

Digiflight II SERIES AUTOPILOTS Operating Handbook For Digiflight II SERIES AUTOPILOTS TRUTRAK FLIGHT SYSTEMS 1500 S. Old Missouri Road Springdale, AR 72764 Ph. 479-751-0250 Fax 479-751-3397 Toll Free: 866-TRUTRAK 866-(878-8725) www.trutrakap.com

More information

UP30 UAV Autopilot System Manual Version 5.7

UP30 UAV Autopilot System Manual Version 5.7 UP30 UAV Autopilot System Manual Version 5.7-0 - CONTENTS Warning, warranty and upgrade.....3 Warning....... 3 Warranty...... 3 Upgrade....... 3 Contact..... 4 Introduction to UP30 Autopilot System....

More information

Mississippi State University Unmanned Aerial Vehicle Entry into the AUVSI 2004 Student UAV Competition

Mississippi State University Unmanned Aerial Vehicle Entry into the AUVSI 2004 Student UAV Competition Mississippi State University Unmanned Aerial Vehicle Entry into the AUVSI 2004 Student UAV Competition Ian Broussard Cornelia Hayes Kelly Lancaster Craig Ross Blake Sanders Mississippi State University

More information

Platform Independent Launch Vehicle Avionics

Platform Independent Launch Vehicle Avionics Platform Independent Launch Vehicle Avionics Small Satellite Conference Logan, Utah August 5 th, 2014 Company Introduction Founded in 2011 The Co-Founders blend Academia and Commercial Experience ~20 Employees

More information

Aerial Photographic System Using an Unmanned Aerial Vehicle

Aerial Photographic System Using an Unmanned Aerial Vehicle Aerial Photographic System Using an Unmanned Aerial Vehicle Second Prize Aerial Photographic System Using an Unmanned Aerial Vehicle Institution: Participants: Instructor: Chungbuk National University

More information

Lightweight Fixed Wing UAV

Lightweight Fixed Wing UAV Lightweight Fixed Wing UAV Cindy Xiao, Rijesh Augustine, Andrew Jowsey, Michael G. Lipsett, Duncan G. Elliott University of Alberta Abstract The University of Alberta Aerial Robotics (UAARG) is a student

More information

DragonLink Advanced Transmitter

DragonLink Advanced Transmitter DragonLink Advanced Transmitter A quick introduction - to a new a world of possibilities October 29, 2015 Written by Dennis Frie Contents 1 Disclaimer and notes for early release 3 2 Introduction 4 3 The

More information

Big Blue Mars Final Report

Big Blue Mars Final Report Big Blue Mars Final Report Member Names Kyle Hart Dale McClure Michael McEwen Contact Information hartman1000@hotmail.com michaelmce@yahoo.com dale.mcclure@uky.edu 2006-04-02 Faculty Advisor Dr. Bill Smith

More information

IMU Platform for Workshops

IMU Platform for Workshops IMU Platform for Workshops Lukáš Palkovič *, Jozef Rodina *, Peter Hubinský *3 * Institute of Control and Industrial Informatics Faculty of Electrical Engineering, Slovak University of Technology Ilkovičova

More information

MICRO AERIAL VEHICLE PRELIMINARY FLIGHT CONTROL SYSTEM

MICRO AERIAL VEHICLE PRELIMINARY FLIGHT CONTROL SYSTEM Multi-Disciplinary Senior Design Conference Kate Gleason College of Engineering Rochester Institute of Technology Rochester, New York 14623 Project Number: 09122 MICRO AERIAL VEHICLE PRELIMINARY FLIGHT

More information

A Survey of UAS Industry Professionals to Guide Program Improvement

A Survey of UAS Industry Professionals to Guide Program Improvement A Survey of Industry Professionals to Guide Program Improvement Saeed M. Khan Kansas State University, Polytechnic Campus Abstract The engineering technology unmanned systems option (ET-US) of K-State

More information

Hopper Spacecraft Simulator. Billy Hau and Brian Wisniewski

Hopper Spacecraft Simulator. Billy Hau and Brian Wisniewski Hopper Spacecraft Simulator Billy Hau and Brian Wisniewski Agenda Introduction Flight Dynamics Hardware Design Avionics Control System Future Works Introduction Mission Overview Collaboration with Penn

More information

If we want to show all the subsystems in the platform, we got the following detailed block diagrams of the platform.

If we want to show all the subsystems in the platform, we got the following detailed block diagrams of the platform. Design and Development of a Networked Control System Platform for Unmanned Aerial Vehicles 1 Yücel Taş, 2 Aydın Yeşildirek, 3 Ahmet Sertbaş 1 Istanbul University, Computer Engineering Dept., Istanbul,

More information

Detrum MSR66A Receiver

Detrum MSR66A Receiver Motion RC User Guide for the Detrum MSR66A Receiver Version 1.0 Contents Review the Receiver s Features... 1 Review the Receiver s Ports and Connection Orientation... 2 Bind the Receiver to a Transmitter

More information

REMOTE AUTONOMOUS MAPPING OF RADIO FREQUENCY OBSTRUCTION DEVICES

REMOTE AUTONOMOUS MAPPING OF RADIO FREQUENCY OBSTRUCTION DEVICES REMOTE AUTONOMOUS MAPPING OF RADIO FREQUENCY OBSTRUCTION DEVICES Team: Jorgen Baertsch, Ian Cooke, Kennedy Harrmann, Mary Landis, Sarah Larson, Harrison Mast, Ethan Morgan, Selby Stout, Jake Ursetta, Justin

More information

Project Bellerophon April 17, 2008

Project Bellerophon April 17, 2008 Project Bellerophon April 17, 2008 Overview Telecommunications Flight Control Power Systems Vehicle Ground Data Processing Inputs Outputs Source Antennas Antennas Sensors Controls Supply Data Channels

More information

Virginia Commonwealth University. Helo UAS. Helicopter Unmanned Aircraft System

Virginia Commonwealth University. Helo UAS. Helicopter Unmanned Aircraft System Helo UAS Helicopter Unmanned Aircraft System Authors: Robert A.Gleich III, Robert C. DeMott II, James W. Homan Lucas Libraro, Skylar Roebuck, Phillip Diana Gus Mancone, David Supola, David West Advisor:

More information

ARDUINO BASED CALIBRATION OF AN INERTIAL SENSOR IN VIEW OF A GNSS/IMU INTEGRATION

ARDUINO BASED CALIBRATION OF AN INERTIAL SENSOR IN VIEW OF A GNSS/IMU INTEGRATION Journal of Young Scientist, Volume IV, 2016 ISSN 2344-1283; ISSN CD-ROM 2344-1291; ISSN Online 2344-1305; ISSN-L 2344 1283 ARDUINO BASED CALIBRATION OF AN INERTIAL SENSOR IN VIEW OF A GNSS/IMU INTEGRATION

More information

User Manual Version 1.0

User Manual Version 1.0 1 Thank you for purchasing our products. The A3 Pro SE controller is the updated version of A3 Pro. After a fully improvement and optimization of hardware and software, we make it lighter, smaller and

More information

Lightweight Fixed Wing UAV

Lightweight Fixed Wing UAV Lightweight Fixed Wing UAV Joseph Patton, Paul Owczarczyk, Mattias Dreger, Jason Bui, Cameron Lee, Cindy Xiao, Rijesh Augustine, Sheldon Marquis, Ryan Kapteyn, Nicholas Kwan Wong, Mark Pollock, Andrew

More information

EzOSD Manual. Overview & Operating Instructions Preliminary. April ImmersionRC EzOSD Manual 1

EzOSD Manual. Overview & Operating Instructions Preliminary. April ImmersionRC EzOSD Manual 1 EzOSD Manual Overview & Operating Instructions Preliminary. April 2009 ImmersionRC EzOSD Manual 1 Contents Overview... 3 Features... 3 Installation... 3 1. Installation using an ImmersionRC camera and

More information

Desktop real time flight simulator for control design

Desktop real time flight simulator for control design Desktop real time flight simulator for control design By T Vijeesh, Technical Officer, FMCD, CSIR-NAL, Bangalore C Kamali, Scientist, FMCD, CSIR-NAL, Bangalore Prem Kumar B, Project Assistant,,FMCD, CSIR-NAL,

More information

GUIDED WEAPONS RADAR TESTING

GUIDED WEAPONS RADAR TESTING GUIDED WEAPONS RADAR TESTING by Richard H. Bryan ABSTRACT An overview of non-destructive real-time testing of missiles is discussed in this paper. This testing has become known as hardware-in-the-loop

More information

THE PERFORMANCE EVALUATION OF AN OFDM-BASED IP TRANSCEIVER AT EGLIN AFB

THE PERFORMANCE EVALUATION OF AN OFDM-BASED IP TRANSCEIVER AT EGLIN AFB THE PERFORMANCE EVALUATION OF AN OFDM-BASED IP TRANSCEIVER AT EGLIN AFB Alfredo Berard, Chief Scientist 46 TSS Eglin AFB, FL USA Paul Cook, Director of RF Products Teletronics Technology Corporation Newtown,

More information

University of Arkansas CSCE Department Capstone I Preliminary Proposal Fall Project Jupiter

University of Arkansas CSCE Department Capstone I Preliminary Proposal Fall Project Jupiter Abstract University of Arkansas CSCE Department Capstone I Preliminary Proposal Fall 2015 Project Jupiter Ben Walcutt, Connor Nesbitt, Emmett Casey, Brian Jones To create an atmospheric testing sounding

More information

SIMGRAPH - A FLIGHT SIMULATION DATA VISUALIZATION WORKSTATION. Joseph A. Kaplan NASA Langley Research Center Hampton, Virginia

SIMGRAPH - A FLIGHT SIMULATION DATA VISUALIZATION WORKSTATION. Joseph A. Kaplan NASA Langley Research Center Hampton, Virginia SIMGRAPH - A FLIGHT SIMULATION DATA VISUALIZATION WORKSTATION Joseph A. Kaplan NASA Langley Research Center Hampton, Virginia Patrick S. Kenney UNISYS Corporation Hampton, Virginia Abstract Today's modern

More information

Height Limited Switch

Height Limited Switch Height Limited Switch Manual version: 1.0 Content Introduction...3 How it works...3 Key features...3 Hardware...4 Motor cut-off settings...4 Specification...4 Using the RC HLS #1 module...5 Powering the

More information

The Next Generation Design of Autonomous MAV Flight Control System SmartAP

The Next Generation Design of Autonomous MAV Flight Control System SmartAP The Next Generation Design of Autonomous MAV Flight Control System SmartAP Kirill Shilov Department of Aeromechanics and Flight Engineering Moscow Institute of Physics and Technology 16 Gagarina st, Zhukovsky,

More information

F-104 Electronic Systems

F-104 Electronic Systems Information regarding the Lockheed F-104 Starfighter F-104 Electronic Systems An article published in the Zipper Magazine # 49 March-2002 Author: Country: Website: Email: Theo N.M.M. Stoelinga The Netherlands

More information

SELF STABILIZING PLATFORM

SELF STABILIZING PLATFORM SELF STABILIZING PLATFORM Shalaka Turalkar 1, Omkar Padvekar 2, Nikhil Chavan 3, Pritam Sawant 4 and Project Guide: Mr Prathamesh Indulkar 5. 1,2,3,4,5 Department of Electronics and Telecommunication,

More information

al T TD ) ime D Faamily Products The RTD Family of products offers a full suite of highprecision GPS sensor positioning and navigation solutions for:

al T TD ) ime D Faamily Products The RTD Family of products offers a full suite of highprecision GPS sensor positioning and navigation solutions for: Reeal ynnamics al T amics (R TD ) ime D RTD) Time Dy Faamily mily ooff P roducts Products The RTD Family of products offers a full suite of highprecision GPS sensor positioning and navigation solutions

More information

Mississippi State University s Entry for the 2005 AUVSI Undergraduate Student Competition

Mississippi State University s Entry for the 2005 AUVSI Undergraduate Student Competition Mississippi State University s Entry for the 2005 AUVSI Undergraduate Student Competition Blake Sanders Craig Ross Nathan Whitfield Ian Broussard Ricky Gray 1.0 Abstract Team Xipiter is Mississippi State

More information

BRB900 GPS Telemetry System August 2013 Version 0.06

BRB900 GPS Telemetry System August 2013 Version 0.06 BRB900 GPS Telemetry System August 2013 Version 0.06 As of January 2013, a new model of the BRB900 has been introduced. The key differences are listed below. 1. U-blox GPS Chipset: The Trimble Lassen IQ

More information

The brain for the plane is the Airelectronics' U-Pilot flight control system, which is embedded inside the plane's fuselage, leaving a lot of space on

The brain for the plane is the Airelectronics' U-Pilot flight control system, which is embedded inside the plane's fuselage, leaving a lot of space on Airelectronics has developed a new complete solution meeting the needs of the farming science. The completely test Skywalkerplatform has been equipped with both thermal and multispectral cameras to measure

More information

MULTI AERIAL SYSTEM STABILIZED IN ALTITUDE FOR INFORMATION MANAGEMENT

MULTI AERIAL SYSTEM STABILIZED IN ALTITUDE FOR INFORMATION MANAGEMENT Review of the Air Force Academy No (7) 4 MULTI AERIAL SYSTEM STABILIZED IN ALTITUDE FOR INFORMATION MANAGEMENT Vasile PRISACARIU*, Ionică CÎRCIU **, Cătălin CIOACĂ**, Mircea BOŞCOIANU**, Andrei LUCHIAN

More information

Trimming your Aerobatic Model

Trimming your Aerobatic Model Trimming your Aerobatic Model When we speak of trimming your aerobatic model we re not talking about trimming in the traditional sense of adjusting the control surfaces to maintain level flight. In this

More information

Experimental Study of Autonomous Target Pursuit with a Micro Fixed Wing Aircraft

Experimental Study of Autonomous Target Pursuit with a Micro Fixed Wing Aircraft Experimental Study of Autonomous Target Pursuit with a Micro Fixed Wing Aircraft Stanley Ng, Frank Lanke Fu Tarimo, and Mac Schwager Mechanical Engineering Department, Boston University, Boston, MA, 02215

More information

Manual for Hyperion Receivers 1. Binding Step 1. Power up the receiver in bind mode

Manual for Hyperion Receivers 1. Binding Step 1. Power up the receiver in bind mode - This is not a Horizon Hobbies DSM2, DSMX product, and is not manufactured or endorsed by Horizon Hobbies LLC. DSM2, and DSMX are registered trademarks of Horizon Hobbies LLC. Manual for Hyperion Receivers

More information

Unmanned Aerial System Competition

Unmanned Aerial System Competition Association for Unmanned Vehicle Systems International Unmanned Aerial System Competition 2007 2008 Design Report Flagship Envy University of California, Los Angeles Abstract A team of undergraduate students

More information

Design of a Miniature Aircraft Deployment System

Design of a Miniature Aircraft Deployment System Project Customer Prof. Eric Frew Project Advisors Prof. Bill Emery Prof. Kurt Maute Design of a Miniature Aircraft Deployment System http://www.colorado.edu/aerospace/mads Leah Crumbaker Jason Farmer Michael

More information

GNSS RFI Detection in Switzerland Based on Helicopter Recording Random Flights

GNSS RFI Detection in Switzerland Based on Helicopter Recording Random Flights Dr. Maurizio Scara muzza, Skyg uide, Heinz Wipf, Skyguide, Dr. Marc Troller, Skyg uide, Heinz Leibundg ut, Sw iss Air-Rescue, René Wittwer, Armasuisse, & Lt. Col. Sergio R ämi, Swiss Air Force GNSS RFI

More information

Design and Navigation Control of an Advanced Level CANSAT. Mansur ÇELEBİ Aeronautics and Space Technologies Institute Turkish Air Force Academy

Design and Navigation Control of an Advanced Level CANSAT. Mansur ÇELEBİ Aeronautics and Space Technologies Institute Turkish Air Force Academy Design and Navigation Control of an Advanced Level CANSAT Mansur ÇELEBİ Aeronautics and Space Technologies Institute Turkish Air Force Academy 1 Introduction Content Advanced Level CanSat Design Airframe

More information

Integrated Navigation System

Integrated Navigation System Integrated Navigation System Adhika Lie adhika@aem.umn.edu AEM 5333: Design, Build, Model, Simulate, Test and Fly Small Uninhabited Aerial Vehicles Feb 14, 2013 1 Navigation System Where am I? Position,

More information

Auvsi 2012 Journal Paper. Abstract ISTANBUL TECHNICAL UNIVERSITY CONTROL & AVIONICS LABORATORY TEAM HEZARFEN

Auvsi 2012 Journal Paper. Abstract ISTANBUL TECHNICAL UNIVERSITY CONTROL & AVIONICS LABORATORY TEAM HEZARFEN ISTANBUL TECHNICAL UNIVERSITY CONTROL & AVIONICS LABORATORY TEAM HEZARFEN Auvsi 2012 Journal Paper Abstract UAS of Team Hezarfen from Istanbul Technical University is explained in this paper. Aerial vehicle

More information

Kongsberg Seatex AS Pirsenteret N-7462 Trondheim Norway POSITION 303 VELOCITY 900 HEADING 910 ATTITUDE 413 HEAVE 888

Kongsberg Seatex AS Pirsenteret N-7462 Trondheim Norway POSITION 303 VELOCITY 900 HEADING 910 ATTITUDE 413 HEAVE 888 WinFrog Device Group: Device Name/Model: Device Manufacturer: Device Data String(s) Output to WinFrog: WinFrog Data String(s) Output to Device: WinFrog Data Item(s) and their RAW record: GPS SEAPATH Kongsberg

More information

Dynamics and Operations of an Orbiting Satellite Simulation. Requirements Specification 13 May 2009

Dynamics and Operations of an Orbiting Satellite Simulation. Requirements Specification 13 May 2009 Dynamics and Operations of an Orbiting Satellite Simulation Requirements Specification 13 May 2009 Christopher Douglas, Karl Nielsen, and Robert Still Sponsor / Faculty Advisor: Dr. Scott Trimboli ECE

More information

Wireless Copilot. Safe2Fly - Height Only Version. Page NanoQuip Ltd

Wireless Copilot. Safe2Fly - Height Only Version. Page NanoQuip Ltd Wireless Copilot Safe2Fly - Height Only Version Page Contents Warnings... 3 Features... 4 Specifications... 5 Installation... 6-8 Receiver Battery... 6 Transmitter Installation... 7-8 How to Use This Manual...

More information

Multi-Vehicles Formation Control Exploring a Scalar Field

Multi-Vehicles Formation Control Exploring a Scalar Field Multi-Vehicles Formation Control Exploring a Scalar Field Polytechnic University Department of Mechanical, Aerospace, and Manufacturing Engineering Polytechnic University,6 Metrotech,, Brooklyn, NY 11201

More information

Midway Design Review. Search And Find Emergency Drone SAFE Drone. Team 4 December 5, 2016

Midway Design Review. Search And Find Emergency Drone SAFE Drone. Team 4 December 5, 2016 Midway Design Review Search And Find Emergency Drone SAFE Drone Team 4 December 5, 2016 Advisor: Professor Leonard 1 Team Members Jamie Kline, EE Serena Thomas, EE Brad Marszalkowski, EE Bjorn Galaske,

More information

GPS Flight Control in UAV Operations

GPS Flight Control in UAV Operations 1 Antenna, GPS Flight Control in UAV Operations CHANGDON KEE, AM CHO, JIHOON KIM, HEEKWON NO SEOUL NATIONAL UNIVERSITY GPS provides position and velocity measurements, from which attitude information can

More information

Delhi College of Engineering 2009 AUVSI STUDENT UAS COMPETITION. Team UAS DCE Journal Paper

Delhi College of Engineering 2009 AUVSI STUDENT UAS COMPETITION. Team UAS DCE Journal Paper Delhi College of Engineering 2009 AUVSI STUDENT UAS COMPETITION Team UAS DCE Journal Paper ABSTRACT The following paper discusses the design and implementation of an Unmanned Aircraft System (UAS) for

More information

The Evolution of Nano-Satellite Proximity Operations In-Space Inspection Workshop 2017

The Evolution of Nano-Satellite Proximity Operations In-Space Inspection Workshop 2017 The Evolution of Nano-Satellite Proximity Operations 02-01-2017 In-Space Inspection Workshop 2017 Tyvak Introduction We develop miniaturized custom spacecraft, launch solutions, and aerospace technologies

More information

Unmanned Air Systems. Naval Unmanned Combat. Precision Navigation for Critical Operations. DEFENSE Precision Navigation

Unmanned Air Systems. Naval Unmanned Combat. Precision Navigation for Critical Operations. DEFENSE Precision Navigation NAVAIR Public Release 2012-152. Distribution Statement A - Approved for public release; distribution is unlimited. FIGURE 1 Autonomous air refuleing operational view. Unmanned Air Systems Precision Navigation

More information