cyberotter

The Cyberotter

Cyberotter is the nickname for ntnu-otter-04, as its initial use was related to cybersecurity by Petter Solnør and Øystein Volden.

The main differences between Cyberotter and the FishOtter are:

  • Navigation: the FishOtter use a Hemisphere proprietary solution for 3DOF position/attitude, while the Cyberotter use a custom setup based on an IMU and two-antenna GNSS. The Cyberotter is also designed to easily fit the SBG Ellipse, and possibly other similar COTS INS.
  • Synchronization: The FishOtter SBC sets up an NTP server that other units can sync to. The Cyberotter extends this by also setting up PTP, which is more accurate than NTP as long as the HW supports it. Both NTP and PTP are supported by many sensors. The Cyberotter also includes a SenTiBoard, which can be used to generate HW trigger signals for e.g. cameras.
  • HW: the Cyberotter use a Beaglebone Black with a custom cape to simplify connections. The BBB has a built-in CAN module, but is not as powerful as the rPi 4 in the FishOtter.
  • The Cyberotter use a custom Linux version, built and setup using the Yocto project. They are documented in the following.

They use the same interface to the Torqueedo board, and rely on the same control, both by Nikolai Lauvås

The Cyberotter is equipped with one Harxon GPS-1000 GNSS survey antenna in the bow and one in the stern, both are connected to its own Ublox F9P-ZED GNSS receiver. The stern receiver (its config)is configured as a ‘moving base’ to send RTCM corrections to the bow (its config), set up as ‘rover’. This enables the bow receiver to precisely calculate heading. This heading is used along with the position of the bow antenna to control the Cyberotter.

As the Otter is underactuated, 2D position and heading is sufficient to control it. A simple improvement would be to use the center position of the two GNSS receivers as the position of the Otter, not the bow receiver.

The Cyberotter is also equipped with an ADIS 16490 IMU. Currently this is only used to log acceleration and angular rate, but could in the future, or offline, be used to aid the position and heading, and also to estimate roll and pitch. TODO: How is the ADIS configured?

Both the GNSS receivers and the IMU are interfaced through the SenTiBoard, to ensure precise timing:

  • Bow GNSS: UART 3
  • Stern GNSS: UART 1
  • IMU: SPI 1

The Cyberotter setup also includes an SBG Ellipse2-D, a standalone INS. This is fed with GNSS signals from the same antennas as the Ublox bow/stern, through antenna splitters. This is included as it is a field-proven INS, and as the Cyberotter itself does not currently provide roll and pitch estimates. The SBG is interfaced with ROS, through the SBG ROS driver. The data from the SBG is also sent to DUNE, for logging, through the ROS IMC bridge.

We use a ROS driver for interfacing with SBG Ellipse 2D: https://github.com/SBG-Systems/sbg_ros_driver.

The IMC ROS bridge developed by the Swedish Maritime Robotics Centre (SMaRC) was used to map ROS topics from the SBG driver to the IMC format. The IMC messages were then transmitted from the Nvidia Jetson to DUNE running on the Beaglebone Black. Link: https://github.com/smarc-project/imc_ros_bridge

The data from the SenTiBoard is parsed in a task in DUNE (Sensors/Sentiboard), that sends out IMC::Acceleration, IMC::AngularRate, IMC:UbxRelPosNED and IMC::GpsFix.

The UbxRelPosNED message is consumed by Sensors/Heading, which: * Generates a heading (IMC::EulerAngles psi) * TODO: determines the center position of the Otter, sent out as another GpsFix message

The Navigation/General task consumes: * GpsFix from Sensors/Heading, as this is the center position for the Otter * EulerAngles from Sensors/Heading, giving yaw which is assembled to an EstimatedState message, dispatched to the controllers (and the rest of DUNE).

To obtain heading from the bow GNSS receiver, the bow GNSS receiver is fed with RTCM corrections from the stern receiver (configured as moving base).

Configuration of u-Blox GNSS receivers is done through the u-center software as follows:

  • Connect the u-Blox GNSS receiver to a computer with u-center installed with a micro-USB to USB cable. Open u-center and connect to the u-Blox receiver by clicking “Receiver → Connection → COMXX” where XX is a number.
  • To configure the u-Blox go to “View → Configuration View”. Configuration of ports and protocol (e.g. UART1, UART2) is done in the “PRT (Ports)” window. Configuration of messages (e.g. RTCM 1074) is done through the “MSG (Messages)” window.
  • After configuring a port, message, or something else, click “Send” in the lower left corner to load the configuration to the u-Blox receiver. Click “Poll” read the current configuration off the u-Blox receiver. After all changes to the u-Blox configuration have been made and loaded, go to “CFG (Configuration)” on the left hand side and enable “Save current configuration” and make sure that both BBR and FLASH are selected (Blue). Click “Send” to write the current configuration to non-volatile memory, to ensure that the configuration is stored after the u-Blox is powered-off.

Following the directions above, set the following configurations (Largely taken from: the Ublox moving base application note):

  • u-Blox Bow GNSS receiver:
    • Configure USB (Protocol in) and (Protocol out) to use UBX+NMEA+RTCM3.
    • Configure UART2 (Protocol in) to use RTCM3 protocol and UART2 (Protocol out) to use NMEA. Set the baudrate to 38400.
    • Configure UART1 (Protocol in) to use UBX+NMEA+RTCM3 and UART1 (Protocol out) to use UBX. Set the baudrate to 230400.
    • In MSG (Messages) enable NMEA-GxGGA, NMEA-GxGLL, NMEA-GxGSA, NMEA-GxGSV, NMEA-GxRMC, NMEA-GxVTG on I2C, UART1, USB, SPI.
    • In MSG (Messages) enable NMEA-GxZDA on UART2.
    • In MSG (Messages) enable NAV-PVT and NAV-RELPOSNED on UART1.
    • In MSG (Messages) enable NAV-HPPOSECEF, NAV-STATUS, NAV-TIMEGPS, NAV-TIMEUTC on UART1, USB.
  • u-Blox Stern GNSS receiver:
    • Configure USB (Protocol in) and (Protocol out) to use UBX+NMEA+RTCM3.
    • Configure UART2 (Protocol in) and (Protocol out) to use RTCM3 protocol. Set the baudrate to 38400.
    • Configure UART1 (Protocol in) to use UBX+NMEA+RTCM3 and (Protocol out) to use UBX. Set the baudrate to 230400.
    • In MSG (Messages) enable NAV-HPPOSECEF, NAV-RELPOSNED, NAV-STATUS, NAV-TIMEGPS, NAV-TIMEUTC, on UART1, USB
    • In MSG (Messages) enable NAV-PVT on UART 1.
    • In MSG (Messages) enable NAV-SAT on UART 2.
    • In MSG (Messages) enable NMEA-GxGGA, NMEA-GxGLL, NMEA-GxGSV, NMEA-GxRMC, NMEA-GxVTG on UART1 and USB.
    • In MSG (Messages) enable RTCM3.3 1074, RTCM3.3 1084, RTCM3.3 1094, RTCM3.3 1124, RTCM3.3 1230 and RTCM3.3 4072 on UART2.
  • To increase the position precision, the moving base is set up to receive RTCM corrections from a stationary RTK base. This is achieved by configuring the RTK base u-Blox as follows:
    • Configure USB (Protocol in) and (Protocol out) to use UBX.
    • Configure UART2 (Protocol in) to none and (Protocol out) to use RTCM3. Set baudrate to 460800.
    • Configure UART1 (Protocol in) and (Protocol out) to use UBX. Set baudrate to 230400.
    • In MSG (Messages) enable NAV-HPPOSECEF, NAV-PVT, , on UART1, USB.
    • In MSG (Messages) enable NAV-SVIN, RXM-RTCM on USB.
    • In MSG (Messages) enable RTCM3.3 1005, RTCM3.3 1074, RTCM3.3 1084, RTCM3.3 1094, RTCM3.3 1124 and RTCM3.3 1230. These RTCM messages are sent to UART4 on the BBB in the RTK base.

The BBB in the RTK base must be configured to pipe the RTCM messages coming into UART2 to a TCP server that the BBB on-board the Cyberotter listens to. This is accomplished by doing the following:

  • The BBB pipes the UART data into a TCP server that the Otter BBB listens to. This is done using str2str of RTKLIB, but does not depend on any RTK-functionality in RTKLIB (it was just the most convenient way to send serial data over ethernet, and might be changed in the future). The following commands are involved:
  • Base BBB, Pipe serial 2 into a virtual serial connection: str2str -in serial://uart/2:460800:8:n:1:off -out serial://../tmp/tty_receiver:460800:8:n:1:off < /dev/null > /dev/null 2>&1 &, then pipe the virtual serial connection to the TCP server: str2str -in serial://../tmp/tty_tcp:460800:8:n:1:off -out tcpsvr://:50025 < /dev/null > /dev/null 2>&1 &.
  • Otter BBB, pipe data from the TCP connection (from the base) out on serial 4: str2str -in tcpcli://10.0.60.195:50025 -out serial://tty04:38400:8:n:1:off, which is started as a service, see recipes-ntnu/rtkclient
  • Configuring UART2RX (UART2 in) of the stern reciever to use RTCM protocol, and connect it to UART4RX of the Otter BBB.

The RTCM3.3 messages described above contain the following information:

   RTCM3.3 1005: Stationary RTK Reference Station Antenna Reference Point (ARP). 
*  RTCM3.3 1074: GPS Type 4 Multiple Signal Message for the American GPS system. 
*  RTCM3.3 1084: GLONASS Type 4 Multiple Signal Message for the Russian GLONASS system.
*  RTCM3.3 1094: Galileo Type 4 Multiple Signal Message for the European Galileo system.
*  RTCM3.3 1124: Beidou Type 4 Multiple Signal Message for the Chinese Beidou system.
*  RTCM3.3 1230: RTCM 1230: GLONASS L1 and L2 Code Phase Biases.
*  RTCM3.3 4072: u-Blox-specific message which provides location and vector data of the moving base (Stern).

Troubleshooting

  • Notice that as the RTK base is a stationary base, it will not send the RTCM3.3 1005 message before a survey-in has been performed. To perform the survey-in, connect the RTK base station u-Blox to u-center and do the following:
    • Go to “View → Configuration View”. Scroll down on the left-hand menu and find “VALSET”.
    • In “Group” select “CFG-TMODE”. Then add “CFG-TMODE-MODE”, “CFG-TMODE-SVIN_MIN_DUR” and “CFG-TMODE-SVIN_ACC_LIMIT” under “Key Name” to list.
    • For each of the Key Names newly added to the list, select the Key Name and click “Get current value” in the lower right corner. This reads the current setting from the u-Blox.
    • Set “CFG-TMODE-MODE” to “1 - SURVEY_IN” to enable survey in.
    • Set “CFG-TMODE-SVIN_MIN_DUR” to a strictly positive number specifying the minimum duration of the survey in procedure in SECONDS.
    • Set “CFG-TMODE-SVIN_ACC_LIMIT” to a strictly positive number specifying the minimum accuray limit of the RTK corrections in increments of 0.1 mm (i.e. a value of 7500 means a minimum accuracy of 75 cm).
    • On the bottom of the menu, select if the survey in settings are to be loaded into Flash, BBR, and/or RAM. If Flash and BBR are selected, the survey in procedure is loaded to non-volatile memory and will always be performed after a power-cycle.
  • To verify that the GNSS receiver is getting RTCM data, check MON-COMMS in Message View in U-center. There is also the Ublox RXM-RTCM message.

The sync “pipeline” is set up as follows: ### PPS ### GPS PPS line is connected to a GPIO pin, and read by the linux kernel, since the PPS kernel module is built in.

The PPS GPIO is set up by the following lines in the device tree file (double check with the yocto repo for the current setup):

    pps {
        pinctrl-names = "default";
        pinctrl-0 = <&pps_pins>;
        compatible = "pps-gpio";
        status = "okay";
        gpios = <&gpio2 6 0>;
        assert-rising-edge;
    };

    pps_pins: pinmux_pps_pins {
        /* lcd_data7 / gpio2_13 */
        pinctrl-single,pins = <0x0a0 (PIN_INPUT_PULLDOWN | MUX_MODE7)>;
    };

If making changes, make sure that the pin you choose is not used/configured for anything else. See device tree configuration

The kernel is configured to include PPS by the following lines in its (def)config:

CONFIG_PPS=y
CONFIG_NTP_PPS=y

With the device tree and kernel changes, a PPS device, like /dev/pps0 shows up. pps-tools are installed in yocto, enabling testing by e.g. ppstest /dev/pps0.

The NTP server use timing information from two sources: PPS and NMEA ZDA.

This relies on the yocto packages ntp, ntp-tickadj, ntpq, ntp-utils, and ntpdc. Once it is set up, you can inspect the NTPD status using ntpq -p, which will print the offset and jitter of the two sources (NMEA and PPS).

PPS

ntp.conf is set up with

# GPS: PPS/ATOM from pps-gpio service
server 127.127.22.0 maxpoll 3 minpoll 5 iburst
fudge 127.127.22.0 refid PPS time1 0.000001
fudge 127.127.22.0 flag3 1

This sets up NTPD to use the PPS Clock discipline found at /dev/pps0 (hence 127.127.22.0), name it PPS (refid PPS), with an initial offset of 0.000001 seconds. See the driver docs for more details.

NMEA ZDA

Sent out by the bow receiver on UART2TX comming in on the BBB on UART5 (/dev/ttyO5).

Using GPSD

Initially, the NMEA message was parsed by GPSD, and shared with NTPD over a shared-memory clock, but this was abandoned to reduce the latency. This can be configured in ntp.conf

GPS Shared Memory Clock from GPSD
server 127.127.28.0 minpoll 3 maxpoll 5 iburst prefer # This must be preferred
fudge 127.127.28.0 refid GPS # Name it GPSD
fudge 127.127.28.0 time1 0.150 flag1 1 # Estimate processing delay offset to 155ms

“The magic pseudo-IP address 127.127.28.0 identifies unit 0 of the ntpd shared-memory driver (NTP0); 127.127.28.1 identifies unit 1 (NTP1).” (from GPSD docs)

GPSD can also parse other messages from the receiver, and will display this information in a CLI invoked by calling gpsmon. The yocto packages used for this setup were gpsd, gps-utils, gpsd-udev, gpsd-conf and gpsd-gpsctl (it is likely that not all are needed).

Directly parsed by NTPD

NTPD can also parse the ZDA NMEA message itself (but only a very limited set of messages, as opposed to GPSD). This is the current setup on the Cyberotter, and is achieved by the following lines in ntp.conf:

# NMEA refclock driver directly from serial port
server 127.127.20.0 mode 56  minpoll 4 iburst prefer true
fudge 127.127.20.0 flag1 0 flag2 0 flag3 0 flag4 0 time1 0.00 refid GPS-NMEA

Mode 56 means linespeed 38400 bps and to process ZDA or ZDG. See NTP driver docs for more information. 127.127.20.X means that NTPD will use the NMEA Reference Clock Driver and listen for messages at /dev/gpsX, while the receiver is connected to /dev/ttyO5. This is fixed by adding the following udev rule (recipes-ntnu/ntp/files/99-gps-name.rules):

KERNEL=="ttyO5", SUBSYSTEM=="tty", SYMLINK+="gps0", RUN+="/bin/stty -F /dev/ttyO5 speed 38400"

The advantage of time sync using PTP is that is a more accurate solution, as it is more HW near, residing in the PHY layer of the stack. This means that you do not need to connect to a server IP to use it, you only need to be plugged in to the same network. Performance hinges on HW support. There are several implementations of the PTP IEEE standard, and the Cyberotter use Linuxptp (installed in yocto using the linuxptp package, with a custom append to set up systemctl services and configuration files). It consists of two parts - ptp4l: the ptp daemon itself - phc2sys: responsible for syncing the PTP clock with the system clock There is also the pmc tool to request status messages from the PTP, e.g. pmc -u -b 0 'get CURRENT_DATA_SET' PTP is set up by following the Ouster PTP guide chapter 15.6.2 Configuring ptp4l as a Local Master Clock and 15.6.3 Configuring phc2sys to Synchronize the System Time to the PTP Clock

Unfortunately, the PTP documentation is poor, but here are some useful links: - Time-sensitive Networking has some tips on what master clock offsets to expect when the clocks are synced (< 100 ns). The values shown by ptp4l and phc2sys logs are in nanoseconds. It also points out the difference between CLOCK_TAI (atomic, i.e. continous) and CLOCK_REALTIME (UTC, which is offset from TAI by an offset that increases as leap seconds are added (37 as of 2017)). - Our working theory is that it does not matter (for these applications) if you use UTC or TAI, as long as you are consistent. - Red Hat Linux PTP guide - List of different Clock classes

ptp4l config

ptp4l -i eth0 -f /etc/ptp4l.conf The config (ptp4l.conf) is the default config for e.g. ubuntu, but clockClass has been set to 6 (master only) for Beaglebone. By this, we force Beaglebone to be PTP grand master clock. Also set priority level 1 and 2 to the same clockclass (6). Leave all other parameters in /etc/ptp4l.conf to default values. The full config is in recipes-ntnu/linuxptp/files/ptp4l.conf.

The Jetson Xavier is a slave in the PTP setup. In /etc/linuxptp/ptp4l.conf , set clockclass to 255 (slave only). Set priority level 1 and 2 to the same clockclass (255). Also, ensure slaveOnly mode is enabled. Leave all other parameters to default values.

phc2sys config

phc2sys is set to sync the Linux CLOCK_REALTIME (as set up by NTPD) to the slave PTP hardware clock of the Ethernet controller (eth0):

phc2sys -w -s CLOCK_REALTIME -c eth0

where -w signifies that it will wait for ptp4l. See recipes-ntnu/linuxptp/files. Any ptp slaves should run phc2sys with the PTP HW clock of the ethernet controller as the master, and CLOCK_REALTIME as slave:

phc2sys -w -c CLOCK_REALTIME -s eth0

Useful commands

Status PTP:

systemctl status ptp4l

Restart PTP:

systemctl restart ptp4l

Check the status of every actor connected:

pmc –u –b 1 ‘GET TIME_STATUS_NP’

Verify that the slaves are in fact configured to be slaves:

pmc –u –b 1 ‘GET SLAVE_ONLY’

The cameras and the LiDAR are interfaced through ROS drivers:

IP info:

Device IP
RTK base BBB 10.0.60.45
Otter BBB 10.0.63.10
Land Rocket AP 192.168.1.20
Otter Bullet 192.168.1.23
Payload Jetson 10.0.63.105
ZED 2 stereo camera X.X.X.X
FLIR camera left 169.254.121.156
FLIR camera right 169.254.123.156
Ouster LIDAR X.X.X.X
  • cyberotter.txt
  • Last modified: 2022/09/19 11:34
  • by 127.0.0.1