diff options
author | Simon Wilks <sjwilks@gmail.com> | 2013-07-04 08:33:19 +0200 |
---|---|---|
committer | Simon Wilks <sjwilks@gmail.com> | 2013-07-04 08:33:19 +0200 |
commit | 6d2f14e125062be623c710c4b739c46be44d0adf (patch) | |
tree | 0df37208e41f8510429c07ce65f2a52efd0b0205 /src/drivers/hott_telemetry/messages.h | |
parent | dadd8703b422523d88b02effe48e76152bcb2fce (diff) | |
download | px4-firmware-6d2f14e125062be623c710c4b739c46be44d0adf.tar.gz px4-firmware-6d2f14e125062be623c710c4b739c46be44d0adf.tar.bz2 px4-firmware-6d2f14e125062be623c710c4b739c46be44d0adf.zip |
Refactoring of the hott telemetry driver and added functionality to read from a HoTT sensor.
Diffstat (limited to 'src/drivers/hott_telemetry/messages.h')
-rw-r--r-- | src/drivers/hott_telemetry/messages.h | 228 |
1 files changed, 0 insertions, 228 deletions
diff --git a/src/drivers/hott_telemetry/messages.h b/src/drivers/hott_telemetry/messages.h deleted file mode 100644 index e1a4262a1..000000000 --- a/src/drivers/hott_telemetry/messages.h +++ /dev/null @@ -1,228 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. - * Author: Simon Wilks <sjwilks@gmail.com> - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file messages.h - * @author Simon Wilks <sjwilks@gmail.com> - * - * Graupner HoTT Telemetry message generation. - * - */ -#ifndef MESSAGES_H_ -#define MESSAGES_H - -#include <stdlib.h> - -/* The HoTT receiver demands a minimum 5ms period of silence after delivering its request. - * Note that the value specified here is lower than 5000 (5ms) as time is lost constucting - * the message after the read which takes some milliseconds. - */ -#define POST_READ_DELAY_IN_USECS 4000 -/* A pause of 3ms is required between each uint8_t sent back to the HoTT receiver. Much lower - * values can be used in practise though. - */ -#define POST_WRITE_DELAY_IN_USECS 2000 - -// Protocol constants. -#define BINARY_MODE_REQUEST_ID 0x80 // Binary mode request. -#define START_BYTE 0x7c -#define STOP_BYTE 0x7d -#define TEMP_ZERO_CELSIUS 0x14 - -#define ESC_SENSOR_ID 0x8e - -/* The ESC Module poll message. */ -struct esc_module_poll_msg { - uint8_t mode; - uint8_t id; -}; - -/* The Electric Air Module message. */ -struct esc_module_msg { - uint8_t start; /**< Start byte */ - uint8_t sensor_id; - uint8_t warning; - uint8_t sensor_text_id; - uint8_t alarm_inverse1; - uint8_t alarm_inverse2; - uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */ - uint8_t temperature2; - uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */ - uint8_t current_H; - uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */ - uint8_t rpm_H; - uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */ - uint8_t speed_H; - uint8_t stop; /**< Stop byte */ - uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ -}; - -/* Electric Air Module (EAM) constants. */ -#define EAM_SENSOR_ID 0x8e -#define EAM_SENSOR_TEXT_ID 0xe0 - -/* The Electric Air Module message. */ -struct eam_module_msg { - uint8_t start; /**< Start byte */ - uint8_t eam_sensor_id; /**< EAM sensor */ - uint8_t warning; - uint8_t sensor_text_id; - uint8_t alarm_inverse1; - uint8_t alarm_inverse2; - uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */ - uint8_t cell2_L; - uint8_t cell3_L; - uint8_t cell4_L; - uint8_t cell5_L; - uint8_t cell6_L; - uint8_t cell7_L; - uint8_t cell1_H; - uint8_t cell2_H; - uint8_t cell3_H; - uint8_t cell4_H; - uint8_t cell5_H; - uint8_t cell6_H; - uint8_t cell7_H; - uint8_t batt1_voltage_L; /**< Battery 1 voltage, lower 8-bits in steps of 0.02V */ - uint8_t batt1_voltage_H; - uint8_t batt2_voltage_L; /**< Battery 2 voltage, lower 8-bits in steps of 0.02V */ - uint8_t batt2_voltage_H; - uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */ - uint8_t temperature2; - uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */ - uint8_t altitude_H; - uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */ - uint8_t current_H; - uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */ - uint8_t main_voltage_H; - uint8_t battery_capacity_L; /**< Used battery capacity in steps of 10mAh */ - uint8_t battery_capacity_H; - uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */ - uint8_t climbrate_H; - uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */ - uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */ - uint8_t rpm_H; - uint8_t electric_min; /**< Flight time in minutes. */ - uint8_t electric_sec; /**< Flight time in seconds. */ - uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */ - uint8_t speed_H; - uint8_t stop; /**< Stop byte */ - uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ -}; - -/** - * The maximum buffer size required to store a HoTT message. - */ -#define EAM_MESSAGE_BUFFER_SIZE sizeof(union { \ - struct eam_module_msg eam; \ -}) - -/* GPS sensor constants. */ -#define GPS_SENSOR_ID 0x8A -#define GPS_SENSOR_TEXT_ID 0xA0 - -/** - * The GPS sensor message - * Struct based on: https://code.google.com/p/diy-hott-gps/downloads - */ -struct gps_module_msg { - uint8_t start; /**< Start byte */ - uint8_t sensor_id; /**< GPS sensor ID*/ - uint8_t warning; /**< Byte 3: 0…= warning beeps */ - uint8_t sensor_text_id; /**< GPS Sensor text mode ID */ - uint8_t alarm_inverse1; /**< Byte 5: 01 inverse status */ - uint8_t alarm_inverse2; /**< Byte 6: 00 inverse status status 1 = no GPS Signal */ - uint8_t flight_direction; /**< Byte 7: 119 = Flightdir./dir. 1 = 2°; 0° (North), 9 0° (East), 180° (South), 270° (West) */ - uint8_t gps_speed_L; /**< Byte 8: 8 = /GPS speed low byte 8km/h */ - uint8_t gps_speed_H; /**< Byte 9: 0 = /GPS speed high byte */ - - uint8_t latitude_ns; /**< Byte 10: 000 = N = 48°39’988 */ - uint8_t latitude_min_L; /**< Byte 11: 231 0xE7 = 0x12E7 = 4839 */ - uint8_t latitude_min_H; /**< Byte 12: 018 18 = 0x12 */ - uint8_t latitude_sec_L; /**< Byte 13: 171 220 = 0xDC = 0x03DC =0988 */ - uint8_t latitude_sec_H; /**< Byte 14: 016 3 = 0x03 */ - - uint8_t longitude_ew; /**< Byte 15: 000 = E= 9° 25’9360 */ - uint8_t longitude_min_L; /**< Byte 16: 150 157 = 0x9D = 0x039D = 0925 */ - uint8_t longitude_min_H; /**< Byte 17: 003 3 = 0x03 */ - uint8_t longitude_sec_L; /**< Byte 18: 056 144 = 0x90 0x2490 = 9360*/ - uint8_t longitude_sec_H; /**< Byte 19: 004 36 = 0x24 */ - - uint8_t distance_L; /**< Byte 20: 027 123 = /distance low byte 6 = 6 m */ - uint8_t distance_H; /**< Byte 21: 036 35 = /distance high byte */ - uint8_t altitude_L; /**< Byte 22: 243 244 = /Altitude low byte 500 = 0m */ - uint8_t altitude_H; /**< Byte 23: 001 1 = /Altitude high byte */ - uint8_t resolution_L; /**< Byte 24: 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */ - uint8_t resolution_H; /**< Byte 25: 117 = High Byte m/s resolution 0.01m */ - uint8_t unknown1; /**< Byte 26: 120 = 0m/3s */ - uint8_t gps_num_sat; /**< Byte 27: GPS.Satellites (number of satelites) (1 byte) */ - uint8_t gps_fix_char; /**< Byte 28: GPS.FixChar. (GPS fix character. display, if DGPS, 2D oder 3D) (1 byte) */ - uint8_t home_direction; /**< Byte 29: HomeDirection (direction from starting point to Model position) (1 byte) */ - uint8_t angle_x_direction; /**< Byte 30: angle x-direction (1 byte) */ - uint8_t angle_y_direction; /**< Byte 31: angle y-direction (1 byte) */ - uint8_t angle_z_direction; /**< Byte 32: angle z-direction (1 byte) */ - uint8_t gyro_x_L; /**< Byte 33: gyro x low byte (2 bytes) */ - uint8_t gyro_x_H; /**< Byte 34: gyro x high byte */ - uint8_t gyro_y_L; /**< Byte 35: gyro y low byte (2 bytes) */ - uint8_t gyro_y_H; /**< Byte 36: gyro y high byte */ - uint8_t gyro_z_L; /**< Byte 37: gyro z low byte (2 bytes) */ - uint8_t gyro_z_H; /**< Byte 38: gyro z high byte */ - uint8_t vibration; /**< Byte 39: vibration (1 bytes) */ - uint8_t ascii4; /**< Byte 40: 00 ASCII Free Character [4] */ - uint8_t ascii5; /**< Byte 41: 00 ASCII Free Character [5] */ - uint8_t gps_fix; /**< Byte 42: 00 ASCII Free Character [6], we use it for GPS FIX */ - uint8_t version; /**< Byte 43: 00 version number */ - uint8_t stop; /**< Byte 44: 0x7D Ende byte */ - uint8_t checksum; /**< Byte 45: Parity Byte */ -}; - -/** - * The maximum buffer size required to store a HoTT message. - */ -#define GPS_MESSAGE_BUFFER_SIZE sizeof(union { \ - struct gps_module_msg gps; \ -}) - -#define MESSAGE_BUFFER_SIZE GPS_MESSAGE_BUFFER_SIZE - -void messages_init(void); -void build_esc_request(uint8_t *buffer, size_t *size); -void extract_esc_message(const uint8_t *buffer); -void build_eam_response(uint8_t *buffer, size_t *size); -void build_gps_response(uint8_t *buffer, size_t *size); -float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next); -void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec); - - -#endif /* MESSAGES_H_ */ |