Skip to content

Commit

Permalink
move driver to separate directory (tmp/backup)
Browse files Browse the repository at this point in the history
  • Loading branch information
flyingthingsintothings committed Mar 22, 2024
1 parent cb39aca commit fa592e2
Show file tree
Hide file tree
Showing 13 changed files with 188 additions and 74 deletions.
1 change: 1 addition & 0 deletions src/drivers/gnss/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
rsource "*/Kconfig"
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ px4_add_module(
SRCS
septentrio.cpp
util.cpp
../devices/src/rtcm.cpp
rtcm.cpp
MODULE_CONFIG
module.yaml
)
5 changes: 5 additions & 0 deletions src/drivers/gnss/septentrio/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
menuconfig DRIVERS_GNSS_SEPTENTRIO
bool "Septentrio GNSS receivers"
default n
---help---
Enable support for Septentrio receivers
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ module_name: Septentrio
parameters:
- group: Septentrio GNSS Receiver
definitions:
SEPT_YAW_OFFS:
SSN_YAW_OFFS:
description:
short: Heading/Yaw offset for dual antenna GPS
long: |
Expand All @@ -23,32 +23,15 @@ parameters:
max: 360
unit: deg
reboot_required: true
SEPT_SAT_INFO:
SSN_SAT_INFO:
description:
short: Enable sat info
long: |
Enable publication of satellite info (ORB_ID(satellite_info)) if possible.
type: boolean
default: 0
reboot_required: true
SEPT_GNSS:
description:
short: GNSS Systems
long: |
This integer bitmask controls the set of GNSS systems used by the receiver.
When no bits are set, the receiver's default configuration is used.
bit:
0: GPS (with QZSS)
1: SBAS (multiple GPS augmentation systems)
2: Galileo
3: BeiDou
4: GLONASS
type: bitmask
default: 0
min: 0
max: 31
reboot_required: true
SEPT_PITCH_OFFS:
SSN_PITCH_OFFS:
description:
short: Pitch offset for dual antenna GPS
long: |
Expand All @@ -65,7 +48,7 @@ parameters:
max: 90
unit: deg
reboot_required: true
SEPT_DUMP_COMM:
SSN_DUMP_COMM:
description:
short: Log GPS communication data
long: |
Expand Down
87 changes: 87 additions & 0 deletions src/drivers/gnss/septentrio/rtcm.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
/****************************************************************************
*
* Copyright (c) 2018 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.
*
****************************************************************************/

#include "rtcm.h"
#include <cstring>

RTCMParsing::RTCMParsing()
{
reset();
}

RTCMParsing::~RTCMParsing()
{
delete[] _buffer;
}

void RTCMParsing::reset()
{
if (!_buffer) {
_buffer = new uint8_t[RTCM_INITIAL_BUFFER_LENGTH];
_buffer_len = RTCM_INITIAL_BUFFER_LENGTH;
}

_pos = 0;
_message_length = _buffer_len;
}

bool RTCMParsing::addByte(uint8_t b)
{
if (!_buffer) {
return false;
}

_buffer[_pos++] = b;

if (_pos == 3) {
_message_length = (((uint16_t)_buffer[1] & 3) << 8) | (_buffer[2]);

if (_message_length + 6 > _buffer_len) {
uint16_t new_buffer_len = _message_length + 6;
uint8_t *new_buffer = new uint8_t[new_buffer_len];

if (!new_buffer) {
delete[](_buffer);
_buffer = nullptr;
return false;
}

memcpy(new_buffer, _buffer, 3);
delete[](_buffer);
_buffer = new_buffer;
_buffer_len = new_buffer_len;
}
}

return _message_length + 6 == _pos;
}
70 changes: 70 additions & 0 deletions src/drivers/gnss/septentrio/rtcm.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
/****************************************************************************
*
* Copyright (c) 2018 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.
*
****************************************************************************/

#pragma once

#include <cstdint>

/* RTCM3 */
#define RTCM3_PREAMBLE 0xD3
#define RTCM_INITIAL_BUFFER_LENGTH 300 /**< initial maximum message length of an RTCM message */


class RTCMParsing
{
public:
RTCMParsing();
~RTCMParsing();

/**
* reset the parsing state
*/
void reset();

/**
* add a byte to the message
* @param b
* @return true if message complete (use @message to get it)
*/
bool addByte(uint8_t b);

uint8_t *message() const { return _buffer; }
uint16_t messageLength() const { return _pos; }
uint16_t messageId() const { return (_buffer[3] << 4) | (_buffer[4] >> 4); }

private:
uint8_t *_buffer{nullptr};
uint16_t _buffer_len{};
uint16_t _pos{}; ///< next position in buffer
uint16_t _message_length{}; ///< message length without header & CRC (both 3 bytes)
};
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -51,44 +51,39 @@
#include <uORB/topics/gps_inject_data.h>
#include <termios.h>

#ifdef __PX4_LINUX
#include <linux/spi/spidev.h>
#endif

#include "septentrio.h"
#include "util.h"
#include "../devices/src/rtcm.h"

#ifndef GPS_READ_BUFFER_SIZE
#define GPS_READ_BUFFER_SIZE 150 ///< Buffer size for `read()` call
#define GPS_READ_BUFFER_SIZE 150 ///< Buffer size for `read()` call
#endif

// TODO: this functionality is not available on the Snapdragon yet
#ifdef __PX4_QURT
#define NO_MKTIME
#endif

#define SBF_CONFIG_TIMEOUT 1000 ///< ms, timeout for waiting ACK
#define SBF_PACKET_TIMEOUT 2 ///< ms, if now data during this delay assume that full update received
#define DISABLE_MSG_INTERVAL 1000000 ///< us, try to disable message with this interval
#define MSG_SIZE 100 ///< size of the message to be sent to the receiver.
#define TIMEOUT_5HZ 500 ///< Timeout time in mS, 1000 mS (1Hz) + 300 mS delta for error
#define RATE_MEASUREMENT_PERIOD 5000000 /// TODO: Document + change back to `5_s` (didn't know what headers to include)
#define RECEIVER_BAUD_RATE 115200 ///< The baudrate of the serial connection to the receiver
#define SBF_CONFIG_TIMEOUT 1000 ///< ms, timeout for waiting ACK
#define SBF_PACKET_TIMEOUT 2 ///< ms, if now data during this delay assume that full update received
#define DISABLE_MSG_INTERVAL 1000000 ///< us, try to disable message with this interval
#define MSG_SIZE 100 ///< size of the message to be sent to the receiver.
#define TIMEOUT_5HZ 500 ///< Timeout time in mS, 1000 mS (1Hz) + 300 mS delta for error
#define RATE_MEASUREMENT_PERIOD 5_s /// TODO: Document + change back to `5_s` (didn't know what headers to include)
#define RECEIVER_BAUD_RATE 115200 ///< The baudrate of the serial connection to the receiver
// TODO: this number seems wrong
#define GPS_EPOCH_SECS ((time_t)1234567890ULL)

/**** Trace macros, disable for production builds */
#define SBF_TRACE_PARSER(...) {/*PX4_INFO(__VA_ARGS__);*/} /* decoding progress in parse_char() */
#define SBF_TRACE_RXMSG(...) {/*PX4_INFO(__VA_ARGS__);*/} /* Rx msgs in payload_rx_done() */
#define SBF_TRACE_PARSER(...) {/*PX4_INFO(__VA_ARGS__);*/} ///< decoding progress in parse_char()
#define SBF_TRACE_RXMSG(...) {/*PX4_INFO(__VA_ARGS__);*/} ///< Rx msgs in payload_rx_done()
#define SBF_INFO(...) {PX4_INFO(__VA_ARGS__);}

/**** Warning macros, disable to save memory */
#define SBF_WARN(...) {PX4_WARN(__VA_ARGS__);}
#define SBF_DEBUG(...) {/*PX4_WARN(__VA_ARGS__);*/}

// Commands
#define SBF_FORCE_INPUT "SSSSSSSSSS\n" /**< Force input on the connected port */
#define SBF_FORCE_INPUT "SSSSSSSSSS\n" /**< Force input on the connected port */

#define SBF_CONFIG_RESET_HOT "" \
SBF_FORCE_INPUT"ExeResetReceiver, soft, none\n"
Expand Down Expand Up @@ -136,7 +131,7 @@ SeptentrioGPS::SeptentrioGPS(const char *device_path) :
_report_gps_pos.heading_offset = NAN;

int32_t enable_sat_info = 0;
param_get(param_find("SEPT_SAT_INFO"), &enable_sat_info);
param_get(param_find("SSN_SAT_INFO"), &enable_sat_info);

/* create satellite info data object if requested */
if (enable_sat_info) {
Expand Down Expand Up @@ -177,7 +172,7 @@ void SeptentrioGPS::run()
{
uint64_t last_rate_measurement = hrt_absolute_time();
unsigned last_rate_count = 0;
param_t handle = param_find("SEPT_YAW_OFFS");
param_t handle = param_find("SSN_YAW_OFFS");
float heading_offset = 0.f;

if (handle != PARAM_INVALID) {
Expand Down Expand Up @@ -430,7 +425,7 @@ int SeptentrioGPS::configure(float heading_offset)
{
_configured = false;

param_t handle = param_find("SEPT_PITCH_OFFS");
param_t handle = param_find("SSN_PITCH_OFFS");
float pitch_offset = 0.f;

if (handle != PARAM_INVALID) {
Expand Down Expand Up @@ -576,24 +571,6 @@ int SeptentrioGPS::serial_open()
return -1;
}

#ifdef __PX4_LINUX

if (_interface == SeptentrioSerialInterface::SPI) {
int spi_speed = 1000000; // make sure the bus speed is not too high (required on RPi)
int status_value = ::ioctl(_serial_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed);

if (status_value < 0) {
PX4_ERR("SPI_IOC_WR_MAX_SPEED_HZ failed for %s (%d)", _port, errno);
}

status_value = ::ioctl(_serial_fd, SPI_IOC_RD_MAX_SPEED_HZ, &spi_speed);

if (status_value < 0) {
PX4_ERR("SPI_IOC_RD_MAX_SPEED_HZ failed for %s (%d)", _port, errno);
}
}

#endif /* __PX4_LINUX */
}

return 0;
Expand Down Expand Up @@ -1128,7 +1105,7 @@ int SeptentrioGPS::write(const uint8_t* buf, size_t buf_length)

void SeptentrioGPS::initialize_communication_dump()
{
param_t handle = param_find("SEPT_DUMP_COMM");
param_t handle = param_find("SSN_DUMP_COMM");
int32_t param_dump_comm;

if (handle == PARAM_INVALID || param_get(handle, &param_dump_comm) != 0) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@
#include <lib/parameters/param.h>

#include "sbf.h"
#include "../devices/src/rtcm.h"
#include "rtcm.h"

/* Message decoder state */
typedef enum {
Expand Down
File renamed without changes.
File renamed without changes.
12 changes: 4 additions & 8 deletions src/drivers/gps/Kconfig
Original file line number Diff line number Diff line change
@@ -1,16 +1,12 @@
menu "GPS"
menuconfig DRIVERS_GPS
menuconfig DRIVERS_GPS
bool "gps"
default n
---help---
Enable support for gps
Enable support for gps

menuconfig USER_GPS
menuconfig USER_GPS
bool "gps running as userspace module"
default y
depends on BOARD_PROTECTED && DRIVERS_GPS
---help---
Put gps in userspace memory

rsource "*/Kconfig"
endmenu #GPS
Put gps in userspace memory
5 changes: 0 additions & 5 deletions src/drivers/gps/septentrio/Kconfig

This file was deleted.

0 comments on commit fa592e2

Please sign in to comment.