forked from Archive/PX4-Autopilot
drives/gps: add new sensor_gnsss_relative msg
- for ublox this corresponds to NAV_RELPOSNED
This commit is contained in:
parent
dfe13e16e8
commit
84e796c385
|
@ -144,6 +144,7 @@ set(msg_files
|
|||
sensor_combined.msg
|
||||
sensor_correction.msg
|
||||
sensor_gps.msg
|
||||
sensor_gnss_relative.msg
|
||||
sensor_gyro.msg
|
||||
sensor_gyro_fft.msg
|
||||
sensor_gyro_fifo.msg
|
||||
|
|
|
@ -0,0 +1,30 @@
|
|||
# GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station.
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp_sample # time since system start (microseconds)
|
||||
|
||||
uint32 device_id # unique device ID for the sensor that does not change between power cycles
|
||||
|
||||
uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0
|
||||
|
||||
uint16 reference_station_id # Reference Station ID
|
||||
|
||||
float32[3] position # GPS NED relative position vector (m)
|
||||
float32[3] position_accuracy # Accuracy of relative position (m)
|
||||
|
||||
float32 heading # Heading of the relative position vector (radians)
|
||||
float32 heading_accuracy # Accuracy of heading of the relative position vector (radians)
|
||||
|
||||
float32 position_length
|
||||
float32 accuracy_length
|
||||
|
||||
bool gnss_fix_ok # GNSS valid fix (i.e within DOP & accuracy masks)
|
||||
bool differential_solution # differential corrections were applied
|
||||
bool relative_position_valid
|
||||
bool carrier_solution_floating # carrier phase range solution with floating ambiguities
|
||||
bool carrier_solution_fixed # carrier phase range solution with fixed ambiguities
|
||||
bool moving_base_mode # if the receiver is operating in moving base mode
|
||||
bool reference_position_miss # extrapolated reference position was used to compute moving base solution this epoch
|
||||
bool reference_observations_miss # extrapolated reference observations were used to compute moving base solution this epoch
|
||||
bool heading_valid
|
||||
bool relative_position_normalized # the components of the relative position vector (including the high-precision parts) are normalized
|
|
@ -43,6 +43,7 @@
|
|||
#include <px4_platform_common/defines.h>
|
||||
#include <uORB/topics/satellite_info.h>
|
||||
#include <uORB/topics/sensor_gps.h>
|
||||
#include <uORB/topics/sensor_gnss_relative.h>
|
||||
|
||||
#define GPS_INFO(...) PX4_INFO(__VA_ARGS__)
|
||||
#define GPS_WARN(...) PX4_WARN(__VA_ARGS__)
|
||||
|
|
|
@ -1 +1 @@
|
|||
Subproject commit fa275c39935e00906d7a691770d2c10f1ea95d3c
|
||||
Subproject commit ad1094aaf16fcc650b270431a1d0bdcf38e8d89a
|
|
@ -63,6 +63,7 @@
|
|||
#include <uORB/topics/gps_dump.h>
|
||||
#include <uORB/topics/gps_inject_data.h>
|
||||
#include <uORB/topics/sensor_gps.h>
|
||||
#include <uORB/topics/sensor_gnss_relative.h>
|
||||
|
||||
#ifndef CONSTRAINED_FLASH
|
||||
# include "devices/src/ashtech.h"
|
||||
|
@ -181,6 +182,8 @@ private:
|
|||
satellite_info_s *_p_report_sat_info{nullptr}; ///< pointer to uORB topic for satellite info
|
||||
|
||||
uORB::PublicationMulti<sensor_gps_s> _report_gps_pos_pub{ORB_ID(sensor_gps)}; ///< uORB pub for gps position
|
||||
uORB::PublicationMulti<sensor_gnss_relative_s> _sensor_gnss_relative_pub{ORB_ID(sensor_gnss_relative)};
|
||||
|
||||
uORB::PublicationMulti<satellite_info_s> _report_sat_info_pub{ORB_ID(satellite_info)}; ///< uORB pub for satellite info
|
||||
|
||||
float _rate{0.0f}; ///< position update rate
|
||||
|
@ -220,6 +223,11 @@ private:
|
|||
*/
|
||||
void publishRTCMCorrections(uint8_t *data, size_t len);
|
||||
|
||||
/**
|
||||
* Publish RTCM corrections
|
||||
*/
|
||||
void publishRelativePosition(sensor_gnss_relative_s &gnss_relative);
|
||||
|
||||
/**
|
||||
* This is an abstraction for the poll on serial used.
|
||||
*
|
||||
|
@ -396,6 +404,13 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user)
|
|||
gps->dumpGpsData((uint8_t *)data1, (size_t)data2, gps_dump_comm_mode_t::RTCM, false);
|
||||
break;
|
||||
|
||||
case GPSCallbackType::gotRelativePositionMessage:
|
||||
if (data1 && data2 == sizeof(sensor_gnss_relative_s)) {
|
||||
gps->publishRelativePosition(*static_cast<sensor_gnss_relative_s *>(data1));
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case GPSCallbackType::surveyInStatus:
|
||||
/* not used */
|
||||
break;
|
||||
|
@ -1184,6 +1199,14 @@ GPS::publishRTCMCorrections(uint8_t *data, size_t len)
|
|||
}
|
||||
}
|
||||
|
||||
void
|
||||
GPS::publishRelativePosition(sensor_gnss_relative_s &gnss_relative)
|
||||
{
|
||||
gnss_relative.device_id = get_device_id();
|
||||
gnss_relative.timestamp = hrt_absolute_time();
|
||||
_sensor_gnss_relative_pub.publish(gnss_relative);
|
||||
}
|
||||
|
||||
int
|
||||
GPS::custom_command(int argc, char *argv[])
|
||||
{
|
||||
|
|
|
@ -176,6 +176,7 @@ void LoggedTopics::add_default_topics()
|
|||
add_optional_topic_multi("sensor_accel", 1000, 4);
|
||||
add_optional_topic_multi("sensor_baro", 1000, 4);
|
||||
add_topic_multi("sensor_gps", 1000, 2);
|
||||
add_topic_multi("sensor_gnss_relative", 1000, 1);
|
||||
add_optional_topic("pps_capture", 1000);
|
||||
add_optional_topic_multi("sensor_gyro", 1000, 4);
|
||||
add_optional_topic_multi("sensor_mag", 1000, 4);
|
||||
|
|
Loading…
Reference in New Issue