PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <ashtech.h>
Public Member Functions | |
GPSDriverAshtech (GPSCallbackPtr callback, void *callback_user, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info, float heading_offset=0.f) | |
virtual | ~GPSDriverAshtech () |
int | receive (unsigned timeout) override |
receive & handle new data from the device More... | |
int | configure (unsigned &baudrate, OutputMode output_mode) override |
configure the device More... | |
Public Member Functions inherited from GPSBaseStationSupport | |
GPSBaseStationSupport (GPSCallbackPtr callback, void *callback_user) | |
virtual | ~GPSBaseStationSupport ()=default |
void | setSurveyInSpecs (uint32_t survey_in_acc_limit, uint32_t survey_in_min_dur) |
set survey-in specs for RTK base station setup (for finding an accurate base station position by averaging the position measurements over time). More... | |
void | setBasePosition (double latitude, double longitude, float altitude, float position_accuracy) |
Set a fixed base station position. More... | |
Public Member Functions inherited from GPSHelper | |
GPSHelper (GPSCallbackPtr callback, void *callback_user) | |
virtual | ~GPSHelper ()=default |
virtual int | reset (GPSRestartType restart_type) |
Reset GPS device. More... | |
float | getPositionUpdateRate () |
float | getVelocityUpdateRate () |
void | resetUpdateRates () |
void | storeUpdateRates () |
Private Member Functions | |
void | decodeInit (void) |
int | handleMessage (int len) |
int | parseChar (uint8_t b) |
int | writeAckedCommand (const void *buf, int buf_length, unsigned timeout) |
Write a command and wait for a (N)Ack. More... | |
int | waitForReply (NMEACommand command, const unsigned timeout) |
void | receiveWait (unsigned timeout_min) |
receive data for at least the specified amount of time More... | |
void | activateCorrectionOutput () |
enable output of correction output More... | |
void | sendSurveyInStatusUpdate (bool active, bool valid, double latitude=(double) NAN, double longitude=(double) NAN, float altitude=NAN) |
void | activateRTCMOutput () |
Private Attributes | |
struct satellite_info_s * | _satellite_info {nullptr} |
struct vehicle_gps_position_s * | _gps_position {nullptr} |
uint64_t | _last_timestamp_time {0} |
NMEADecodeState | _decode_state {NMEADecodeState::uninit} |
uint8_t | _rx_buffer [ASHTECH_RECV_BUFFER_SIZE] |
uint16_t | _rx_buffer_bytes {} |
bool | _got_pashr_pos_message {false} |
If we got a PASHR,POS message, we will ignore GGA messages. More... | |
NMEACommand | _waiting_for_command |
NMEACommandState | _command_state {NMEACommandState::idle} |
char | _port {'A'} |
port we are connected to (e.g. More... | |
AshtechBoard | _board {AshtechBoard::other} |
board we are connected to More... | |
RTCMParsing * | _rtcm_parsing {nullptr} |
gps_abstime | _survey_in_start {0} |
OutputMode | _output_mode {OutputMode::GPS} |
bool | _correction_output_activated {false} |
bool | _configure_done {false} |
float | _heading_offset |
Additional Inherited Members | |
Public Types inherited from GPSHelper | |
enum | OutputMode : uint8_t { OutputMode::GPS = 0, OutputMode::RTCM } |
enum | Interface : uint8_t { Interface::UART = 0, Interface::SPI } |
Protected Types inherited from GPSBaseStationSupport | |
enum | BaseSettingsType : uint8_t { BaseSettingsType::survey_in, BaseSettingsType::fixed_position } |
Protected Member Functions inherited from GPSHelper | |
int | read (uint8_t *buf, int buf_length, int timeout) |
read from device More... | |
int | write (const void *buf, int buf_length) |
write to the device More... | |
int | setBaudrate (int baudrate) |
set the Baudrate More... | |
void | surveyInStatus (SurveyInStatus &status) |
void | gotRTCMMessage (uint8_t *buf, int buf_length) |
got an RTCM message from the device More... | |
void | setClock (timespec &t) |
Static Protected Member Functions inherited from GPSHelper | |
static void | ECEF2lla (double ecef_x, double ecef_y, double ecef_z, double &latitude, double &longitude, float &altitude) |
Convert an ECEF (Earth Centered Earth Fixed) coordinate to LLA WGS84 (Lat, Lon, Alt). More... | |
Protected Attributes inherited from GPSBaseStationSupport | |
BaseSettings | _base_settings |
Protected Attributes inherited from GPSHelper | |
GPSCallbackPtr | _callback {nullptr} |
void * | _callback_user {} |
uint8_t | _rate_count_lat_lon {} |
uint8_t | _rate_count_vel {} |
float | _rate_lat_lon {0.0f} |
float | _rate_vel {0.0f} |
uint64_t | _interval_rate_start {0} |
|
strongprivate |
|
strongprivate |
|
strongprivate |
|
strongprivate |
GPSDriverAshtech::GPSDriverAshtech | ( | GPSCallbackPtr | callback, |
void * | callback_user, | ||
struct vehicle_gps_position_s * | gps_position, | ||
struct satellite_info_s * | satellite_info, | ||
float | heading_offset = 0.f |
||
) |
heading_offset | heading offset in radians [-pi, pi]. It is substracted from the measurement. |
Definition at line 53 of file ashtech.cpp.
References decodeInit().
|
virtual |
Definition at line 64 of file ashtech.cpp.
References _rtcm_parsing.
|
private |
enable output of correction output
Definition at line 1135 of file ashtech.cpp.
References GPSBaseStationSupport::_base_settings, _correction_output_activated, _output_mode, _survey_in_start, activateRTCMOutput(), GPSBaseStationSupport::FixedPositionSettings::altitude, ASH_DEBUG, ASH_RESPONSE_TIMEOUT, GPSBaseStationSupport::BaseSettings::fixed_position, gps_absolute_time, GPSBaseStationSupport::FixedPositionSettings::latitude, GPSBaseStationSupport::FixedPositionSettings::longitude, GPSBaseStationSupport::SurveyInSettings::min_dur, RECEIPT, GPSHelper::RTCM, sendSurveyInStatusUpdate(), GPSBaseStationSupport::BaseSettings::settings, GPSBaseStationSupport::survey_in, GPSBaseStationSupport::BaseSettings::survey_in, GPSBaseStationSupport::BaseSettings::type, waitForReply(), GPSHelper::write(), and writeAckedCommand().
Referenced by handleMessage().
|
private |
Definition at line 727 of file ashtech.cpp.
References _port, ASH_DEBUG, ASH_RESPONSE_TIMEOUT, and writeAckedCommand().
Referenced by activateCorrectionOutput(), and handleMessage().
|
overridevirtual |
configure the device
baud | Input and output parameter: if set to 0, the baudrate will be automatically detected and set to the detected baudrate. If not 0, a fixed baudrate is used. |
Implements GPSHelper.
Definition at line 943 of file ashtech.cpp.
References _board, _configure_done, _correction_output_activated, _output_mode, _port, ASH_DEBUG, ASH_RESPONSE_TIMEOUT, decodeInit(), GPSHelper::GPS, PRT, receiveWait(), RID, GPSHelper::RTCM, GPSHelper::setBaudrate(), status, GPSHelper::surveyInStatus(), trimble_mb_two, waitForReply(), GPSHelper::write(), and writeAckedCommand().
|
private |
Definition at line 904 of file ashtech.cpp.
References _decode_state, _output_mode, _rtcm_parsing, _rx_buffer_bytes, RTCMParsing::reset(), GPSHelper::RTCM, and uninit.
Referenced by configure(), GPSDriverAshtech(), and parseChar().
|
private |
< GPS ground speed (m/s)
< GPS ground speed in m/s
< GPS ground speed in m/s
< GPS ground speed in m/s
< Course over ground (NOT heading, but direction of movement) in rad, -PI..PI
< Flag to indicate if NED speed is valid
knots to m/s
GPS ground speed (m/s)
GPS ground speed in m/s
GPS ground speed in m/s
GPS ground speed in m/s
Course over ground (NOT heading, but direction of movement) in rad, -PI..PI
Flag to indicate if NED speed is valid
Definition at line 76 of file ashtech.cpp.
References GPSBaseStationSupport::_base_settings, _board, _command_state, _configure_done, _correction_output_activated, _got_pashr_pos_message, _gps_position, _heading_offset, _last_timestamp_time, _output_mode, _port, GPSHelper::_rate_count_lat_lon, GPSHelper::_rate_count_vel, _rx_buffer, _satellite_info, _survey_in_start, _waiting_for_command, Acked, activateCorrectionOutput(), activateRTCMOutput(), vehicle_gps_position_s::alt, ASH_DEBUG, ASH_UNUSED, satellite_info_s::azimuth, vehicle_gps_position_s::c_variance_rad, vehicle_gps_position_s::cog_rad, satellite_info_s::count, satellite_info_s::elevation, vehicle_gps_position_s::eph, vehicle_gps_position_s::epv, f(), vehicle_gps_position_s::fix_type, gps_absolute_time, GPS_EPOCH_SECS, vehicle_gps_position_s::hdop, vehicle_gps_position_s::heading, vehicle_gps_position_s::lat, vehicle_gps_position_s::lon, M_PI_F, MIN, GPSBaseStationSupport::SurveyInSettings::min_dur, nack, other, PRT, RECEIPT, received, RID, GPSHelper::RTCM, vehicle_gps_position_s::s_variance_m_s, vehicle_gps_position_s::satellites_used, sendSurveyInStatusUpdate(), GPSHelper::setClock(), GPSBaseStationSupport::BaseSettings::settings, satellite_info_s::snr, GPSBaseStationSupport::BaseSettings::survey_in, satellite_info_s::svid, vehicle_gps_position_s::time_utc_usec, vehicle_gps_position_s::timestamp, satellite_info_s::timestamp, vehicle_gps_position_s::timestamp_time_relative, trimble_mb_two, satellite_info_s::used, vehicle_gps_position_s::vdop, vehicle_gps_position_s::vel_d_m_s, vehicle_gps_position_s::vel_e_m_s, vehicle_gps_position_s::vel_m_s, vehicle_gps_position_s::vel_n_m_s, vehicle_gps_position_s::vel_ned_valid, and waiting.
Referenced by receive().
|
private |
Definition at line 829 of file ashtech.cpp.
References _decode_state, _rtcm_parsing, _rx_buffer, _rx_buffer_bytes, RTCMParsing::addByte(), ASH_DEBUG, decode_rtcm3, decodeInit(), got_asteriks, got_first_cs_byte, got_sync1, GPSHelper::gotRTCMMessage(), HEXDIGIT_CHAR, RTCMParsing::message(), RTCMParsing::messageLength(), RTCM3_PREAMBLE, and uninit.
Referenced by receive().
|
overridevirtual |
receive & handle new data from the device
timeout | [ms] |
Implements GPSHelper.
Definition at line 769 of file ashtech.cpp.
References gps_absolute_time, GPS_READ_BUFFER_SIZE, handleMessage(), parseChar(), and GPSHelper::read().
Referenced by receiveWait(), and waitForReply().
|
private |
receive data for at least the specified amount of time
Definition at line 760 of file ashtech.cpp.
References gps_absolute_time, and receive().
Referenced by configure().
|
private |
Definition at line 1224 of file ashtech.cpp.
References GPSBaseStationSupport::_base_settings, GPSBaseStationSupport::SurveyInSettings::min_dur, GPSBaseStationSupport::BaseSettings::settings, status, GPSBaseStationSupport::BaseSettings::survey_in, and GPSHelper::surveyInStatus().
Referenced by activateCorrectionOutput(), and handleMessage().
|
private |
Definition at line 927 of file ashtech.cpp.
References _command_state, _waiting_for_command, ASH_DEBUG, command, gps_absolute_time, receive(), received, and waiting.
Referenced by activateCorrectionOutput(), configure(), and writeAckedCommand().
|
private |
Write a command and wait for a (N)Ack.
Definition at line 918 of file ashtech.cpp.
References Acked, waitForReply(), and GPSHelper::write().
Referenced by activateCorrectionOutput(), activateRTCMOutput(), and configure().
|
private |
board we are connected to
Definition at line 131 of file ashtech.h.
Referenced by configure(), and handleMessage().
|
private |
Definition at line 129 of file ashtech.h.
Referenced by handleMessage(), and waitForReply().
|
private |
Definition at line 139 of file ashtech.h.
Referenced by configure(), and handleMessage().
|
private |
Definition at line 138 of file ashtech.h.
Referenced by activateCorrectionOutput(), configure(), and handleMessage().
|
private |
Definition at line 123 of file ashtech.h.
Referenced by decodeInit(), and parseChar().
|
private |
If we got a PASHR,POS message, we will ignore GGA messages.
Definition at line 126 of file ashtech.h.
Referenced by handleMessage().
|
private |
Definition at line 120 of file ashtech.h.
Referenced by handleMessage().
|
private |
Definition at line 141 of file ashtech.h.
Referenced by handleMessage().
|
private |
Definition at line 121 of file ashtech.h.
Referenced by handleMessage().
|
private |
Definition at line 137 of file ashtech.h.
Referenced by activateCorrectionOutput(), configure(), decodeInit(), and handleMessage().
|
private |
port we are connected to (e.g.
'A')
Definition at line 130 of file ashtech.h.
Referenced by activateRTCMOutput(), configure(), and handleMessage().
|
private |
Definition at line 133 of file ashtech.h.
Referenced by decodeInit(), parseChar(), and ~GPSDriverAshtech().
|
private |
Definition at line 124 of file ashtech.h.
Referenced by handleMessage(), and parseChar().
|
private |
Definition at line 125 of file ashtech.h.
Referenced by decodeInit(), and parseChar().
|
private |
Definition at line 119 of file ashtech.h.
Referenced by handleMessage().
|
private |
Definition at line 135 of file ashtech.h.
Referenced by activateCorrectionOutput(), and handleMessage().
|
private |
Definition at line 128 of file ashtech.h.
Referenced by handleMessage(), and waitForReply().