mcsauder
4 years ago
committed by
Beat Küng
7 changed files with 112 additions and 6 deletions
@ -1,9 +1,10 @@
@@ -1,9 +1,10 @@
|
||||
uint64 timestamp # time since system start (microseconds) |
||||
uint8 SAT_INFO_MAX_SATELLITES = 20 |
||||
|
||||
uint8 count # Number of satellites in satellite info |
||||
uint8 count # Number of satellites visible to the receiver |
||||
uint8[20] svid # Space vehicle ID [1..255], see scheme below |
||||
uint8[20] used # 0: Satellite not used, 1: used for navigation |
||||
uint8[20] elevation # Elevation (0: right on top of receiver, 90: on the horizon) of satellite |
||||
uint8[20] azimuth # Direction of satellite, 0: 0 deg, 255: 360 deg. |
||||
uint8[20] snr # dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. |
||||
uint8[20] prn # Satellite PRN code assignment, (psuedorandom number SBAS, valid codes are 120-144) |
||||
|
@ -0,0 +1,97 @@
@@ -0,0 +1,97 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved. |
||||
* |
||||
* 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#ifndef GPS_STATUS_HPP |
||||
#define GPS_STATUS_HPP |
||||
|
||||
#include <uORB/topics/satellite_info.h> |
||||
|
||||
class MavlinkStreamGPSStatus : public MavlinkStream |
||||
{ |
||||
public: |
||||
const char *get_name() const override { return MavlinkStreamGPSStatus::get_name_static(); } |
||||
|
||||
static constexpr const char *get_name_static() { return "GPS_STATUS"; } |
||||
|
||||
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_GPS_STATUS; } |
||||
|
||||
uint16_t get_id() override { return get_id_static(); } |
||||
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamGPSStatus(mavlink); } |
||||
|
||||
unsigned get_size() override |
||||
{ |
||||
return _satellite_info_sub.advertised() ? MAVLINK_MSG_ID_GPS_STATUS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0; |
||||
} |
||||
|
||||
private: |
||||
uORB::Subscription _satellite_info_sub{ORB_ID(satellite_info)}; |
||||
|
||||
// Disallow copy and move construction.
|
||||
MavlinkStreamGPSStatus(MavlinkStreamGPSStatus &) = delete; |
||||
MavlinkStreamGPSStatus &operator = (const MavlinkStreamGPSStatus &) = delete; |
||||
|
||||
protected: |
||||
explicit MavlinkStreamGPSStatus(Mavlink *mavlink) : MavlinkStream(mavlink) |
||||
{} |
||||
|
||||
bool send() override |
||||
{ |
||||
satellite_info_s sat {}; |
||||
|
||||
if (_satellite_info_sub.update(&sat)) { |
||||
mavlink_gps_status_t msg{}; |
||||
|
||||
msg.satellites_visible = sat.count; |
||||
|
||||
size_t sat_count = math::min(static_cast<size_t>(sat.count), |
||||
sizeof(msg.satellite_used) / sizeof(msg.satellite_used[0])); |
||||
|
||||
for (size_t i = 0; i < sat_count; i++) { |
||||
msg.satellite_used[i] = sat.used[i]; |
||||
msg.satellite_elevation[i] = sat.elevation[i]; |
||||
msg.satellite_azimuth[i] = sat.azimuth[i]; |
||||
msg.satellite_snr[i] = sat.snr[i]; |
||||
msg.satellite_prn[i] = sat.prn[i]; |
||||
} |
||||
|
||||
mavlink_msg_gps_status_send_struct(_mavlink->get_channel(), &msg); |
||||
|
||||
return true; |
||||
} |
||||
|
||||
return false; |
||||
} |
||||
}; |
||||
|
||||
#endif // GPS_STATUS_HPP
|
Loading…
Reference in new issue