GPS tested and working

This commit is contained in:
Lorenz Meier 2012-10-25 13:07:26 +02:00
parent 4d03d020af
commit 2b9cf08dc2
2 changed files with 21 additions and 17 deletions

View File

@ -50,6 +50,7 @@
#define UBX_HEALTH_SUCCESS_COUNTER_LIMIT 2
#define UBX_HEALTH_FAIL_COUNTER_LIMIT 2
#define UBX_HEALTH_PROBE_COUNTER_LIMIT 4
#define UBX_BUFFER_SIZE 1000
@ -242,9 +243,9 @@ int ubx_parse(uint8_t b, char *gps_rx_buffer)
ubx_gps->timestamp = hrt_absolute_time();
ubx_gps->counter++;
pthread_mutex_lock(ubx_mutex);
//pthread_mutex_lock(ubx_mutex);
ubx_state->last_message_timestamps[NAV_POSLLH - 1] = hrt_absolute_time();
pthread_mutex_unlock(ubx_mutex);
//pthread_mutex_unlock(ubx_mutex);
ret = 1;
} else {
@ -273,9 +274,9 @@ int ubx_parse(uint8_t b, char *gps_rx_buffer)
ubx_gps->counter++;
pthread_mutex_lock(ubx_mutex);
//pthread_mutex_lock(ubx_mutex);
ubx_state->last_message_timestamps[NAV_SOL - 1] = hrt_absolute_time();
pthread_mutex_unlock(ubx_mutex);
//pthread_mutex_unlock(ubx_mutex);
ret = 1;
} else {
@ -305,9 +306,9 @@ int ubx_parse(uint8_t b, char *gps_rx_buffer)
ubx_gps->counter++;
pthread_mutex_lock(ubx_mutex);
//pthread_mutex_lock(ubx_mutex);
ubx_state->last_message_timestamps[NAV_DOP - 1] = hrt_absolute_time();
pthread_mutex_unlock(ubx_mutex);
//pthread_mutex_unlock(ubx_mutex);
ret = 1;
} else {
@ -351,9 +352,9 @@ int ubx_parse(uint8_t b, char *gps_rx_buffer)
ubx_gps->counter++;
pthread_mutex_lock(ubx_mutex);
//pthread_mutex_lock(ubx_mutex);
ubx_state->last_message_timestamps[NAV_TIMEUTC - 1] = hrt_absolute_time();
pthread_mutex_unlock(ubx_mutex);
//pthread_mutex_unlock(ubx_mutex);
ret = 1;
} else {
@ -452,9 +453,9 @@ int ubx_parse(uint8_t b, char *gps_rx_buffer)
ubx_gps->counter++;
pthread_mutex_lock(ubx_mutex);
//pthread_mutex_lock(ubx_mutex);
ubx_state->last_message_timestamps[NAV_SVINFO - 1] = hrt_absolute_time();
pthread_mutex_unlock(ubx_mutex);
//pthread_mutex_unlock(ubx_mutex);
ret = 1;
} else {
@ -484,9 +485,9 @@ int ubx_parse(uint8_t b, char *gps_rx_buffer)
ubx_gps->counter++;
pthread_mutex_lock(ubx_mutex);
//pthread_mutex_lock(ubx_mutex);
ubx_state->last_message_timestamps[NAV_VELNED - 1] = hrt_absolute_time();
pthread_mutex_unlock(ubx_mutex);
//pthread_mutex_unlock(ubx_mutex);
ret = 1;
} else {
@ -518,9 +519,9 @@ int ubx_parse(uint8_t b, char *gps_rx_buffer)
ubx_gps->counter++;
pthread_mutex_lock(ubx_mutex);
//pthread_mutex_lock(ubx_mutex);
ubx_state->last_message_timestamps[RXM_SVSI - 1] = hrt_absolute_time();
pthread_mutex_unlock(ubx_mutex);
//pthread_mutex_unlock(ubx_mutex);
ret = 1;
} else {
@ -700,6 +701,7 @@ int write_config_message_ubx(uint8_t *message, size_t length, int fd)
unsigned int result_write = write(fd, message, length);
result_write += write(fd, &ck_a, 1);
result_write += write(fd, &ck_b, 1);
fsync(fd);
return (result_write != length + 2); //return 0 as success
@ -759,7 +761,7 @@ void *ubx_watchdog_loop(void *args)
/* If we have too many failures and another mode or baud should be tried, exit... */
if ((gps_mode_try_all == true || gps_baud_try_all == true) && (ubx_fail_count >= UBX_HEALTH_FAIL_COUNTER_LIMIT) && (ubx_healthy == false) && once_ok == false) {
if ((gps_mode_try_all == true || gps_baud_try_all == true) && (ubx_fail_count >= UBX_HEALTH_PROBE_COUNTER_LIMIT) && (ubx_healthy == false) && once_ok == false) {
if (gps_verbose) printf("[gps] Connection attempt failed, no UBX module found\r\n");
gps_mode_success = false;

View File

@ -1,7 +1,7 @@
/****************************************************************************
*
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -35,6 +35,8 @@
/**
* @file mavlink_bridge_header
* MAVLink bridge header for UART access.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
*/
/* MAVLink adapter header */