AP_GPS: switch fields to add units suffix

altitude -> altitude_cm
ground_speed -> ground_speed_cm
ground_course -> ground_course_cd

this helps prevent unit mixups
This commit is contained in:
Andrew Tridgell 2013-07-10 14:01:53 +10:00
parent 7aa360b176
commit 7dbb898264
8 changed files with 30 additions and 30 deletions

View File

@ -35,10 +35,10 @@ void AP_GPS_HIL::setHIL(uint32_t _time, float _latitude, float _longitude, float
time = _time; time = _time;
latitude = _latitude*1.0e7f; latitude = _latitude*1.0e7f;
longitude = _longitude*1.0e7f; longitude = _longitude*1.0e7f;
altitude = _altitude*1.0e2f; altitude_cm = _altitude*1.0e2f;
ground_speed = _ground_speed*1.0e2f; ground_speed_cm = _ground_speed*1.0e2f;
ground_course = _ground_course*1.0e2f; ground_course_cd = _ground_course*1.0e2f;
speed_3d = _speed_3d*1.0e2f; speed_3d_cm = _speed_3d*1.0e2f;
num_sats = _num_sats; num_sats = _num_sats;
fix = FIX_3D; fix = FIX_3D;
new_data = true; new_data = true;

View File

@ -147,9 +147,9 @@ restart:
} }
latitude = _swapl(&_buffer.msg.latitude) * 10; latitude = _swapl(&_buffer.msg.latitude) * 10;
longitude = _swapl(&_buffer.msg.longitude) * 10; longitude = _swapl(&_buffer.msg.longitude) * 10;
altitude = _swapl(&_buffer.msg.altitude); altitude_cm = _swapl(&_buffer.msg.altitude);
ground_speed = _swapl(&_buffer.msg.ground_speed); ground_speed_cm = _swapl(&_buffer.msg.ground_speed);
ground_course = _swapl(&_buffer.msg.ground_course) / 10000; ground_course_cd = _swapl(&_buffer.msg.ground_course) / 10000;
num_sats = _buffer.msg.satellites; num_sats = _buffer.msg.satellites;
// time from gps is UTC, but convert here to msToD // time from gps is UTC, but convert here to msToD

View File

@ -151,9 +151,9 @@ restart:
latitude = _buffer.msg.latitude; latitude = _buffer.msg.latitude;
longitude = _buffer.msg.longitude; longitude = _buffer.msg.longitude;
} }
altitude = _buffer.msg.altitude; altitude_cm = _buffer.msg.altitude;
ground_speed = _buffer.msg.ground_speed; ground_speed_cm = _buffer.msg.ground_speed;
ground_course = _buffer.msg.ground_course; ground_course_cd = _buffer.msg.ground_course;
num_sats = _buffer.msg.satellites; num_sats = _buffer.msg.satellites;
hdop = _buffer.msg.hdop; hdop = _buffer.msg.hdop;
date = _buffer.msg.utc_date; date = _buffer.msg.utc_date;

View File

@ -241,12 +241,12 @@ bool AP_GPS_NMEA::_term_complete()
date = _new_date; date = _new_date;
latitude = _new_latitude * 10; // degrees*10e5 -> 10e7 latitude = _new_latitude * 10; // degrees*10e5 -> 10e7
longitude = _new_longitude * 10; // degrees*10e5 -> 10e7 longitude = _new_longitude * 10; // degrees*10e5 -> 10e7
ground_speed = _new_speed; ground_speed_cm = _new_speed;
ground_course = _new_course; ground_course_cd = _new_course;
fix = GPS::FIX_3D; // To-Do: add support for proper reporting of 2D and 3D fix fix = GPS::FIX_3D; // To-Do: add support for proper reporting of 2D and 3D fix
break; break;
case _GPS_SENTENCE_GPGGA: case _GPS_SENTENCE_GPGGA:
altitude = _new_altitude; altitude_cm = _new_altitude;
time = _new_time; time = _new_time;
latitude = _new_latitude * 10; // degrees*10e5 -> 10e7 latitude = _new_latitude * 10; // degrees*10e5 -> 10e7
longitude = _new_longitude * 10; // degrees*10e5 -> 10e7 longitude = _new_longitude * 10; // degrees*10e5 -> 10e7
@ -255,8 +255,8 @@ bool AP_GPS_NMEA::_term_complete()
fix = GPS::FIX_3D; // To-Do: add support for proper reporting of 2D and 3D fix fix = GPS::FIX_3D; // To-Do: add support for proper reporting of 2D and 3D fix
break; break;
case _GPS_SENTENCE_GPVTG: case _GPS_SENTENCE_GPVTG:
ground_speed = _new_speed; ground_speed_cm = _new_speed;
ground_course = _new_course; ground_course_cd = _new_course;
// VTG has no fix indicator, can't change fix status // VTG has no fix indicator, can't change fix status
break; break;
} }

View File

@ -180,11 +180,11 @@ AP_GPS_SIRF::_parse_gps(void)
} }
latitude = _swapl(&_buffer.nav.latitude); latitude = _swapl(&_buffer.nav.latitude);
longitude = _swapl(&_buffer.nav.longitude); longitude = _swapl(&_buffer.nav.longitude);
altitude = _swapl(&_buffer.nav.altitude_msl); altitude_cm = _swapl(&_buffer.nav.altitude_msl);
ground_speed = _swapi(&_buffer.nav.ground_speed); ground_speed_cm = _swapi(&_buffer.nav.ground_speed);
// at low speeds, ground course wanders wildly; suppress changes if we are not moving // at low speeds, ground course wanders wildly; suppress changes if we are not moving
if (ground_speed > 50) if (ground_speed_cm > 50)
ground_course = _swapi(&_buffer.nav.ground_course); ground_course_cd = _swapi(&_buffer.nav.ground_course);
num_sats = _buffer.nav.satellites; num_sats = _buffer.nav.satellites;
return true; return true;

View File

@ -221,7 +221,7 @@ AP_GPS_UBLOX::_parse_gps(void)
time = _buffer.posllh.time; time = _buffer.posllh.time;
longitude = _buffer.posllh.longitude; longitude = _buffer.posllh.longitude;
latitude = _buffer.posllh.latitude; latitude = _buffer.posllh.latitude;
altitude = _buffer.posllh.altitude_msl / 10; altitude_cm = _buffer.posllh.altitude_msl / 10;
fix = next_fix; fix = next_fix;
_new_position = true; _new_position = true;
break; break;
@ -265,9 +265,9 @@ AP_GPS_UBLOX::_parse_gps(void)
break; break;
case MSG_VELNED: case MSG_VELNED:
Debug("MSG_VELNED"); Debug("MSG_VELNED");
speed_3d = _buffer.velned.speed_3d; // cm/s speed_3d_cm = _buffer.velned.speed_3d; // cm/s
ground_speed = _buffer.velned.speed_2d; // cm/s ground_speed_cm = _buffer.velned.speed_2d; // cm/s
ground_course = _buffer.velned.heading_2d / 1000; // Heading 2D deg * 100000 rescaled to deg * 100 ground_course_cd = _buffer.velned.heading_2d / 1000; // Heading 2D deg * 100000 rescaled to deg * 100
_have_raw_velocity = true; _have_raw_velocity = true;
_vel_north = _buffer.velned.ned_north; _vel_north = _buffer.velned.ned_north;
_vel_east = _buffer.velned.ned_east; _vel_east = _buffer.velned.ned_east;

View File

@ -74,7 +74,7 @@ GPS::update(void)
if (_status >= GPS_OK_FIX_2D) { if (_status >= GPS_OK_FIX_2D) {
last_fix_time = _idleTimer; last_fix_time = _idleTimer;
_last_ground_speed_cm = ground_speed; _last_ground_speed_cm = ground_speed_cm;
if (_have_raw_velocity) { if (_have_raw_velocity) {
// the GPS is able to give us velocity numbers directly // the GPS is able to give us velocity numbers directly
@ -82,8 +82,8 @@ GPS::update(void)
_velocity_east = _vel_east * 0.01f; _velocity_east = _vel_east * 0.01f;
_velocity_down = _vel_down * 0.01f; _velocity_down = _vel_down * 0.01f;
} else { } else {
float gps_heading = ToRad(ground_course * 0.01f); float gps_heading = ToRad(ground_course_cd * 0.01f);
float gps_speed = ground_speed * 0.01f; float gps_speed = ground_speed_cm * 0.01f;
float sin_heading, cos_heading; float sin_heading, cos_heading;
cos_heading = cosf(gps_heading); cos_heading = cosf(gps_heading);

View File

@ -103,10 +103,10 @@ public:
uint32_t date; ///< GPS date (FORMAT TBD) uint32_t date; ///< GPS date (FORMAT TBD)
int32_t latitude; ///< latitude in degrees * 10,000,000 int32_t latitude; ///< latitude in degrees * 10,000,000
int32_t longitude; ///< longitude in degrees * 10,000,000 int32_t longitude; ///< longitude in degrees * 10,000,000
int32_t altitude; ///< altitude in cm int32_t altitude_cm; ///< altitude in cm
uint32_t ground_speed; ///< ground speed in cm/sec uint32_t ground_speed_cm; ///< ground speed in cm/sec
int32_t ground_course; ///< ground course in 100ths of a degree int32_t ground_course_cd; ///< ground course in 100ths of a degree
int32_t speed_3d; ///< 3D speed in cm/sec (not always available) int32_t speed_3d_cm; ///< 3D speed in cm/sec (not always available)
int16_t hdop; ///< horizontal dilution of precision in cm int16_t hdop; ///< horizontal dilution of precision in cm
uint8_t num_sats; ///< Number of visible satelites uint8_t num_sats; ///< Number of visible satelites