Control System Software

Overview

The RAMA system software is relatively complex and consists of the programs running on its three on-board computers - the Main Control Computer (MCC), the Data Acquisition Module (DAM) and the Servo Control Unit (SCU) - and on the Ground Station (GS). The DAM and SCU programs are running system-less (without any operating system), while the MCC and GS both use the Linux operating system. Any Linux distributions, utilizing kernel version 2.6.19 or above can be used. The MCC program does not have any special requirements, although FIFO scheduling policy must be supported, as the real-time thread priorities are used. The GS software requires the QT library 4.2.x or higher.

Basic Principles of Function

rama_working_cycle.jpg

Basically, RAMA is a synchronous time-triggered system, working at the 64Hz frequency, although some of the events can happen asynchronously (those related to various failure modes) and some of the data (the GPS provided data) are sampled at a different frequency. All three main nodes of the system (the MCC, the DAM and the SCU) are communicating solely via the Vehicle Bus (VB). The DAM provides the rest of the system with the Time Synchronization Message (TSM), sent periodically 64 times per second. This message determines the working cycle of the system - it marks the end of current working cycle and the beginning of the next. This is how all three nodes are commonly synchronized.

At the beginning of each working cycle, the data sampling and processing is taking place. Upon sending the TSM, the DAM prepares the latest sensor data (inertial measurements taken from the IMU and magnetic measurements from the TAM), and sends them to the MCC. The TSM also triggers sampling and sending of the control stick positions in the SCU.

The TSM prompts the MCC to force-finish the current working cycle (in case it did not end already) and wait for the new data acquisition. The force-finish should never occur under normal circumstances, as the regular working cycle should end well before the start of the new cycle. Occurrence of the force-finish indicates that something went wrong in the last cycle and is reported via telemetry as an error notification (see section Main Control Computer Software Framework).

Upon receiving the essential measurements for the control algorithms, the MCC executes the control loop, which computes the new control actions. Afterwards, newly computed actions are fed into the SCU (which applies them at the beginning of the next actuator control period). When all measurements for the current cycle are completed and received, the synchronous Telemetry Measurement Message (TMM) is composed and sent to the Ground Station (GS) via the Wireless Data Communication Unit (WDCU).

The GPS data are sampled and processed independently, at 1Hz sampling rate. This is not ideal, but there is no other way, because it is not possible to synchronize the IMU and the GPS (both are stand-alone units with their own internal timing). There is no control over their sampling points, nor any way to synchronize them. In fact, the TSM is derived directly from the IMU sampling point, so the RAMA system timing is built around the IMU timing. On the other hand, it is not a major problem either; the GPS data can be processed fairly independently in the control algorithms and does not necessarily need to be precisely synchronous with the rest of the data.

In its current state of development, RAMA can operate in two control modes - either in the Manual Control Mode (MCM), when the vehicle is fully controlled by a human pilot, and RAMA serves only as a telemetry device; or in the Automatic Control Mode (ACM), when RAMA takes over some (or all) actuators. From the controller development point of view, it is sometimes convenient if automatic control could be applied only to some selected actuators, while the others are controlled manually; that’s the reason why this option was implemented.

In both control modes, the operating cycle is almost exactly the same; there are two differences though. The first one resides in the control action computation. In the MCM, the action is computed, but the integrator state of the controller is set so that its output value equals the corresponding control stick position (see section SISO PID Controller Structure) - this is done to provide the bumpless transition from the MCM to the ACM. The other difference is that the SCU does not apply received action values to the actuators; it applies the stick position signals directly to the actuator control signals.

The communication protocol of the Vehicle Bus (VB) is relatively simple. Short 11-bit IDs are used and the priority of each message is determined by its ID (the lower the ID is the higher is the priority). The bit rate is 1Mbps (the maximum for the CAN bus). The messages are broadcast and each node receives all the messages; however, it ignores all messages that do not affect his own operation. Complete list of VB messages along with their meaning is shown in the table below.

Complete List of the Vehicle Bus Messages

ID Meaning Contents
DAM Status Messages - out
0×0002 IMU error uint8 error code
0×0004 GPS error uint8 error code
0×0064 DAM boot-up no data
DAM Data Messages - out
0×0014 TSM Message no data
0×0020 x magnetic intensity float raw data float filtered (miligauss)
0×0040 y magnetic intensity float raw data float filtered (miligauss)
0×0060 z magnetic intensity float raw data float filtered (miligauss)
0×0056 x acceleration float raw data float filtered (milig)
0×0057 y acceleration float raw data float filtered (milig)
0×0058 z acceleration float raw data float filtered (milig)
0x00C4 angular rate roll float raw data float filtered (rad/s)
0x01C4 angular rate pitch float raw data float filtered (rad/s)
0x03C4 angular rate yaw float raw data float filtered (rad/s)
0×0400 GPS raw data 1 uint64 raw data
0×0200 GPS raw data 2 uint64 raw data
0×0180 GPS raw data 3 uint64 raw data
0×0100 GPS raw data 4 uint64 raw data
0×0300 GPS raw data 5 uint64 raw data
0×0500 GPS raw data 6 uint64 raw data
0×0700 GPS raw data 7 uint64 raw data
0×0090 GPS raw data 8 uint64 raw data
DAM Command Messages - in
0×0059 calibration sample number uint16 number
0x006E DAM reset request no data
0x006F DAM run request no data
0×0070 roll rate filter a coef. float coefficient
0×0071 roll rate filter b coef. float coefficient
0×0072 pitch rate filter a coef. float coefficient
0×0073 pitch rate filter b coef. float coefficient
0×0074 yaw rate filter a coef. float coefficient
0×0075 yaw rate filter b coef. float coefficient
0×0076 accel x filter a coef. float coefficient
0×0077 accel x rate filter b coef. float coefficient
0×0078 accel y filter a coef. float coefficient
0×0079 accel y rate filter b coef. float coefficient
0x007A accel z filter a coef. float coefficient
0x007B accel z rate filter b coef. float coefficient
0x007C TAM x filter a coef. float coefficient
0x007D TAM x rate filter b coef. float coefficient
0x007E TAM y filter a coef. float coefficient
0x007F TAM y rate filter b coef. float coefficient
0×0080 TAM z filter a coef. float coefficient
0×0081 TAM z rate filter b coef. float coefficient
0×0082 TAM x offset float offset
0×0083 TAM y offset float offset
0×0084 TAM z offset float offset
SCU Status Messages - out
0×0005 SCU error uint8 error code
0x000A ACM engaged no data
0x000B MCM engaged no data
SCU Data Messages - out
0×0023 stick positions 1 uint8 servo mask uint8 reserved uint16 throttle uint16 roll uint16 pitch
0×0024 stick positions 2 uint16 gyro uint16 collective uint16 yaw uint16 reserved
0×0032 battery voltages uint8 ACB voltage uint8 AVB voltage
SCU Command Messages - in
0×0019 servo positions 1 uint8 servo mask uint8 reserved uint16 throttle uint16 roll uint16 pitch
0x001A servo positions 2 uint16 gyro uint16 collective uint16 yaw uint16 reserved

Let us now describe the telemetry communication protocol. There are several types of messages, distinguished by their identificator (ID). Messages are character-encoded (meaning that a message can only contain characters), so the numbers are sent as byte-strings in hexadecimal format (for example, a float number is sent in the form of its memory representation, i.e. as a four-byte number, where each byte is represented by two characters in the telemetry message). Each message starts with the starting character @, followed by the two-character message ID (the ID is a hexadecimal number in the range of 00-FF). Optionally, some data may follow. The messages do not have a termination character, nor are they secured by a CRC or any other consistency check; it is assumed that the TCP/IP protocol takes care of all this, so it would be redundant.

There are several asynchronous messages, which can be sent anytime; these are used to indicate asynchronous events, such as the error conditions on the control mode transition (ACM/MCM or reversed).

Two synchronous data messages are used, each sent in different time intervals. The first message contains all measurements except the GPS data and is sent 64 times per second (corresponding to the working cycle frequency of the RAMA system), while the other contains the GPS data and is sent once in a second (corresponding to the GPS sampling rate). Complete list of the telemetry messages can be found in the table below.

Complete List of the Telemetry Messages

ID Meaning Contents
Asynchronous Messages
0×02 IMU error uint8 error code
0×04 GPS error uint8 error code
0×05 SCU error uint8 error code
0×10 control mode uint8 mode (0×00-MCM 0xFF-ACM)
0×30 data composition error uint32 error code
0×64 DAM unexpected reset uint8 number of occurrences
Synchronous Data Messages
0×35 all data sampled @64Hz struct eth_data_msg_type data
0×40 GPS data sampled @1Hz struct cpo_pvt_data_type gps_data

Definition of the Data Structures

 typedef struct {
    uint32_t sample_num;
    uint8_t servo_mask;
    uint8_t reserve_1;
    int16_t throttle_stick_pos;
    int16_t roll_stick_pos;
    int16_t pitch_stick_pos;
    int16_t gyro_stick_pos;
    int16_t collective_stick_pos;
    int16_t yaw_stick_pos;
    int16_t reserve_2;
    float des_roll;
    float des_pitch;
    float des_yaw;
    int16_t throttle_servo_pos;
    int16_t roll_servo_pos;
    int16_t pitch_servo_pos;
    int16_t yaw_servo_pos;
    int16_t collective_servo_pos;
    int16_t reserve_3;
    float params_roll_rate_Xi;
    float params_roll_rate_Xdr;
    float params_roll_rate_Xdy;
    float params_pitch_rate_Xi;
    float params_pitch_rate_Xdr;
    float params_pitch_rate_Xdy;
    float params_yaw_rate_Xi;
    float params_yaw_rate_Xdr;
    float params_yaw_rate_Xdy;
    float batt_voltage_actuator;
    float batt_voltage_avionic;
    float roll_angle;
    float pitch_angle;
    float yaw_angle;
    float angular_rate_roll_filtered;
    float angular_rate_pitch_filtered;
    float angular_rate_yaw_filtered;
    float angular_rate_roll;
    float angular_rate_pitch;
    float angular_rate_yaw;
    float accel_x_filtered;
    float accel_y_filtered;
    float accel_z_filtered;
    float accel_x;
    float accel_y;
    float accel_z;
    float mfi_x_filtered;
    float mfi_y_filtered;
    float mfi_z_filtered;
    float mfi_x;
    float mfi_y;
    float mfi_z;
 } __attribute__ ( ( packed ) ) eth_data_msg_type;
 typedef struct {
    float alt;
    float epe;
    float eph;
    float epv;
    int16_t fix;
    double gps_tow;
    double lat;
    double lon;
    float lon_vel;
    float lat_vel;
    float alt_vel;
    float msl_hght;
    int16_t leap_sec;
    int32_t grmn_days;
 } __attribute__ ( ( packed ) ) cpo_pvt_data_type;

The telemetry communication is one-way, no data are sent from the Ground Station (GS) to the Airborne Part (AP) of the system. Multiple Ground Stations are allowed; The Airborne Part provides a data server and the telemetry can be broadcast among multiple clients.

Main Control Computer Software Framework

The MCC program is decomposed into several libraries and the main program. The libraries contain functions for CAN and TCP/IP communications, the PID control algorithm and several support functions, while the main program contains the rest. It can be compiled using the powerpc-603e-linux-gnu-gcc cross-compiler, preferably version 4.1.x or later (the program is tested and known to be working with gcc 4.1.1). The source code is available in the download section here here (registration required). To build the project, just enter the directory “rama_main” and call “make”. If you have the PowerPC toolchain installed, it should work. Step-by-step guidelines on how to install the cross-compiler for PowerPC and how to compile and install the Linux on the Boa5200 board (currently used as the MCC) can be found here.

Let us now briefly describe the supporting libraries first, and the main program later.

The controller Library

The controller library consists of two functions. The function PID_init serves to initialize the structure, holding the internal parameters and state variables of the controller. The second function, called PID_control, contains the control algorithm itself. More details on that algorithm can be found in section SISO PID Controller Structure.

The cancomm Library

This is a very simple support library for CAN communications. SocketCAN is used, therefore the basic communication mechanism is exactly the same as for any other socket communication. The header file of this library contains definition of the CAN device identificators and the IDs of the CAN messages. This is not ideal though, as the message IDs are also defined in the DAM software, so there are actually two places where the definitions can be found; therefore, when editing an ID number (or adding one), two files have to be modified. This is because some legacy software was used, and shall be rectified in future software revisions (maybe =)).

The sole function contained in this library serves for the CAN device initialization, and is pretty self-explanatory (see the comments in the source code).

The ipcomm Library

The ipcomm library contains functions allowing one to set-up a simple server for the socket communication. This server is capable to handle multiple clients and broadcasts the telemetry messages. The server runs aboard the RAMA system, while the Ground Station (GS) is a client.

The header file of the library contains several constant definitions, such as various buffer lengths, the server port number and the bitwise data flags. Those flags are used to check for the data consistency in each sampling period; as each data part is written into the data holding structure for each data message, corresponding flag is set to indicate that the data have been properly updated.

The data holding structures for both synchronous messages are defined in the header file. Note that the GPS data structure consists only of a 64-byte long array and the data consistency variable - that is because the GPS data are currently not used for any on-board calculations, and therefore do not need to be parsed. Therefore, they are recorded into the array directly as they are received from the DAM and re-sent to the GS, and no decoding and processing takes place in the on-board software. Naturally, this will change with later software revisions, introducing navigation and guidance algorithms.

Basically, the server is running in two separate threads. One thread takes care of the client management, an the other for broadcasting data to all active clients.

The “client management thread” (function server) checks for activity on any of the socket filedescriptors, that is on the server socket and the active client sockets. The select function is used to handle multiple events in a single program thread. If a new client connects to the server socket, new socket is created for it and the file descriptor of this new socket is added into the active_fd_set list. When one of the active clients closes connection, it is removed from the list and the corresponding filedescriptor is closed. This list is used by the “broadcast thread” to send the data to all active clients.

The “Broadcast thread” (function send_packet_thread) checks the output data round buffer for any unsent data and broadcasts them to all active clients. The write function is blocking - it does not resume until all data are sent and their reception is acknowledged by the recipient. Therefore, should any communication problems occur, this thread would be suspended until the data are received properly by all the clients. In the meantime, all upcoming data are stored into the output round buffer by the sending threads. The size of this buffer is sufficient to handle up to 15 minute-long communication hangups. The buffer is statically allocated, so its size is constant - no dynamic allocations are used anywhere in the code for safety reasons, as is common in embedded system software. When the buffer is full, the oldest data are simply overwritten (as is normal in round buffers). The function send_packet is used by the other threads to submit data into the output round buffer - so it does not send the data directly. This function is non-blocking, so the submitting thread cannot be suspended because of possible communication problem.

The endconv Library

This primitive library is used for the endian conversions. The MCC software is written so that it can be compiled for the little or big endian architectures alike, without the need for any modifications.

The open_device library

Pretty self-explanatory, this tiny library contains functions to open/close block devices.

Main Program

mcc_working_cycle.jpg

RAMA’s main MCC program consists of four threads, each running in an infinite loop. Two threads are responsible for the telemetry broadcasting (see section The ipcomm Library, one for the Vehicle Bus (VB) communication and the last one for the control algorithm execution. The program is event-driven, so the control actions are triggered by data reception from the VB.

The working cycle of the program is determined by the Time Synchronization Message (TSM), provided by the DAM. Upon receiving this message, the next working cycle begins. The VB messages are received and processed by the read_from_can_thread, which reads the message and calls the processing function, somewhat obscurely called send_ip_msg. This is because of some historical reasons and should be renamed and modified in the future.

This function is switched according the message ID and does the basic processing. After receiving all the data needed for the controller to run (determined by the reception flags), a semaphore is set, which in turn enables the servo_control_thread to run. When all data for the Telemetry Measurement Message (TMM) are gathered, the message is composed and submitted to the telemetry buffer, and the working cycle is finished. If next TSM is received prior to the end of the previous cycle, this cycle is force-finished - the missing data are not updated (in fact, the last values remain recorded in the data reading structure) and the Telemetry Data Composition Error (TDCE) message is generated.

The servo_control_thread begins with the initialization of the controllers for the ARCL and ACL control layers, and then enters an infinite cycle. At the beginning of each cycle the thread waits for the synchronization semaphore (controller_enable) to be set. Afterwards, all the input values are copied into its local variables (to prevent a possible racing condition) and the normalization of the control stick positions is done. Control actions are computed afterwards - in the current version (7.1), only the Angular Rate Control Layer (ARCL) and Attitude Control Layer (ACL) are implemented. The ACL, if enabled, works as an attitude holder; it works only when the control sticks are in neutral positions. In that case, it provides the reference for the ARCL. If the ACL layer is disabled or the corresponding control stick is not in the neutral position, the ACL is inactive and the control stick position provides the reference for the ARCL (the desired angular rate).

When the computation is finished, the resulting control actions are de-normalized (servo positions are computed) and resulting commands are sent to the Servo Control Unit (SCU).

Before starting all the threads and entering the working cycle, the main program performs the initialization. A command is sent to the Data Acquisition Module (DAM) to reset itself. Then all the parameters (controller and filter parameters and other stuff) are read from the configuration file. Some of these parameters are sent over to the DAM, using the Vehicle Bus (VB). This is all done by the control_init function. The regular working cycle is not entered before the sensor calibration is performed. The length of the calibration process is determined by the cal_sample_count variable, which is read from the configuration file and determines the number of calibration samples. This procedure is used to determine the neutral positions of the control sticks and the offsets of the gyroscopes. It is assumed that the vehicle stands still during the calibration process and the control sticks are in their neutral positions. The angular rates, provided by the gyroscopes during the calibration process, are sampled and their mean value is computed for each gyroscope. This mean value is then subtracted from the corresponding gyroscope measurements in the run-time, to compensate for its offset. Same algorithm is used to determine the neutral positions of the control sticks.

Data Acquisition Module Software

dam_working_cycle.jpg

The Data Acquisition Module (DAM) runs system-less. The program is relatively complicated though, and utilizes the resources of the Philips LPC 2119 MCU (Micro Controller Unit) to a relatively great extent. This is mainly because the numerical filtration of the measurements is taking place here, computed in the float numbers, and three separate devices must be monitored (The Inertial Measurement Unit or IMU, the Global Positioning System or GPS and the Three Axis Magnetometer or TAM). To achieve greater precision, the TAM is internally sampled at 512Hz (although the results are averaged and sent out along with the IMU data at 64Hz). The IMU is sampled at 64Hz, as was said many times before, and the GPS at 1Hz. Both IMU and GPS are “intelligent” units and have serial interfaces, sending digital datapackets. The IMU is connected to the UART0 and the GPS to the UART1 ports of the MCU. The TAM is an analog device, giving three-channel voltage measurements proportional to the magnetic intensities, and is connected to the A/D converter (channels ADC0, ADC1 and ADC2).

The three ADC channels cannot be scanned successively, one after another, in a single time step; the error in the sample and hold circuitry of the LPC 2119 prevents this. Therefore, each channel is scanned separately in adjacent time steps. The timing is provided by the timer T0. This timer is running at 1536Hz; This means that the measurements of all three axes are acquired 512 times per second (therefore the overall sampling frequency is 512Hz).

PWM channel PWM2 is used to provide a 1kHz signal for the Villard (Delon) step-up voltage converter (this voltage is being used to generate the periodic degauss pulses for the TAM).

Several simple libraries are utilized to access the peripherals, namely the CAN, UART and PWM. These libraries are heritage pieces of code and their detailed description is beyond the scope of this thesis. They are relatively simple and well documented in their source files.

The program starts with the initialization of the peripherals. The internal PLL of the MCU is set to multiply the external clock six times, therefore (with external 10MHz crystal) provides the internal core clock at 60MHz. The peripheral clock is set to the same frequency. The Vector Interrupt Controller (VIC) and the PIO (Parallel Input-Output ports) are initialized immediately after, followed by the PWM, CAN controller and watchdog. A loop is entered afterwards, awaiting the reception of the configuration parameters (the number of the calibration samples and the filter parameters). After receiving all required parameters, the rest of the peripherals are initialized (the ADC, both UARTs and the timer T0) and the main program loop is entered. In this loop, new data reception flags are checked for both UARTs and the CAN. The incoming data from each of these peripherals are read in their interrupt handlers and stored into separate round buffers.

When data are received from the UART0, the IMU_service function is called. This function contains a simple state-machine, which receives and decodes the datapackets provided by the IMU. The Time Synchronization Message (TSM) is also generated here. Any problems, detected during datapacket reception and decoding, are reported via error messages. When the process is completed and newly acquired data are filtered, they are broadcast on the Vehicle Bus (VB) (which is the CAN), both the raw samples and the filtered data.

UART1 data reception indicates the new GPS data arrival, and the GPS_service function is called to process them. Similarly to the previous case, there is a simple state machine taking care of the data. When complete datapacket is received, it is broadcast on the VB. No data decoding or processing is applied.

In the case of the VB (CAN) data reception, the can_rx function is called. It mainly serves to receive the initial parameters before the main loop of the program is entered; In the run-time, all but one message are ignored. The only message not to be ignored is the command to reset. If this command is received, the watchdog resetting (which is normally taking place in the timer T0 handler) is disabled, and therefore the watchdog itself triggers the MCU reset. This is the most simple and reliable way to ensure a clean MCU restart.

The source code of the DAM firmware can be found here (registration required). You will need to install proper toolchain for the ARM7TDMI core before compiling the project; You can find a step-by-step guide here. Once you have the toolchain in place, just unpack the tarball and call “make”, and the project should build. The source code of the main program can be found in the directory “app/rama_dam”. The libraries are located in “arch/arm/mach-lpc21xx/libs”. The compiled binary may be found in “compiled/bin” (ELF format). You can upload the firmware into the MCU using for example the lpc21isp (Local copy of the lpc21isp binary is here). If you use lpc21isp, you will need to convert the binary file into the Intel HEX format. Use binutils for that purpose. The program is tested and known to be working with gcc 4.3.2. To upload the firmware into the DAM, use the following sequence:

  • Connect to the UART0 of the DAM (some kind of RS-232/3.3V or RS-232/TTL adapter is necessary; the pins of the LPC2119 are 5V tolerant and the link is known to be working with the RS-232/TTL adapter).
  • Ground the ISPSEL pin.
  • Power-up the DAM, then ground the RESET pin temporarily to ensure proper MCU reset. The internal ISP bootloader of the LPC2119 should be running now.
  • Convert the binary from the ELF to the Intel HEX format by calling: “arm-elf-objcopy -O ihex in_file_name.elf out_file_name.hex”
  • Call “./lpc21isp file_name.hex /dev/ttyS0 38400 10000” (instead of “TTYS0” naturally fill in the device name you use). The parameter “38400” is the baud rate, “10000” is the clock frequency in kHz - the DAM uses 10MHz crystal.
  • Disconnect the ISPSEL and reset the MCU. If the firmware was uploaded correctly, all four LEDs should illuminate, heralding the boot-up.
  • Enjoy =)!

Servo Control Unit Firmware

The Servo Control Unit Software is running system-less. It was designed and implemented by Ota Herm, my former graduate student, who also designed the hardware. The documentation is currently only available in the Czech language only and can be found in Ota's master thesis. It will be translated into English as soon as I find some time (or somebody =)) to do it.

If you want to compile the program, you will need the h8300-coff-gcc, version 3.5.x (no later version!!! - there is a known compatibility issue with the gcc 4.x.x revisions). A step-by-step guide on the instalation can be found here.

The SCU software is very old and have not been modified since 2005. You can download the SCU firmware here (registration required). It is configured to work, so if you have the cross-compiler installed, just unpack the file somewhere and call make” - it should work and build the program. To upload the firmware to the SCU, two steps are needed: First, you need to install the Bloader bootloader into the MCU; The firmware itself is updated using the Bloader. In order to install the Bloader, you need to:

  • Disconnect the J20 jumper to disable FLASH memory write protection.
  • Connect the J22 jumper to enable bootloader upload.
  • Connect to the SCU using the COM1 UART (some RS-232/TTL adapter is needed).
  • Reset the MCU by disconnecting the J21 (to disable watchdog resetting) and connect the J18 (watchdog reset).
  • Now disconnect the J18 jumper on the SCU to disable the watchdog.
  • Enter the “app/bloader” directory and call “make bootstrap” - the Bloader should upload.
  • Disconnect the J22.
  • Reset the MCU again - If the Bloader was uploaded properly, some LEDs should illuminate.

To install the firmware, do the following:

  • Enter the “board/h8heli/servodrv” directory and call make load-flash. The firmware should upload now.
  • Connect the J18, J20 and J21 jumpers to enable watchdog and FLASH memory write protection. The MCU should reset now (because of the watchdog) and the application should start. The LEDs should illuminate and the D2 LED should start flashing.
  • Enjoy =)!

Ground Station

ground_station.jpg

The Ground Station (GS) was designed and implemented by Petr Svoboda, my former graduate student, as his master thesis. The source codes are available in the download section here (registration required) and can be compiled using gcc 4.1.x or later. You also need the QT 4.5.0 or later in order to compile and run it. The documentation of this complex software is currently available in the Czech language only in Petr's master thesis; it will be translated into English as soon as I find some time (or somebody =)) to do it. More info on this project can be found at Petr's website.

If you don’t need complex Graphical User Interface (GUI), a very primitive, but working telemetry recorder is available to download here (registration required). This program is deprecated and would not be documented, but feel free to use it if you like – it has only negligible hardware demands, as it has no GUI (it runs in the terminal and uses the ncurses library). It is small, reliable and does its job (that is recording the telemetry into a text file and showing some important data on-line) just fine. It can be used (and, in fact, is being used by us) as an alternative, very simple Ground Station. To build it, just call “make” and use an arbitrary gcc version - it should work =).

 
control_system_software.txt · Last modified: 07/01/2010 09:07 by ondra
 
Recent changes RSS feed Creative Commons License Powered by PHP Valid XHTML 1.0 Valid CSS Driven by DokuWiki