Skip to content

Commit

Permalink
Iridium driver and support
Browse files Browse the repository at this point in the history
Mavlink module implement HIGH_LATENCY (Iridium)
  • Loading branch information
dagar authored and LorenzMeier committed Dec 14, 2016
1 parent 77e482a commit bce7ecb
Show file tree
Hide file tree
Showing 14 changed files with 1,450 additions and 16 deletions.
5 changes: 5 additions & 0 deletions ROMFS/px4fmu_common/init.d/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -600,6 +600,11 @@ then
then
mavlink start -d $MAVLINK_COMPANION_DEVICE -b 57600 -r 1000
fi
if param compare SYS_COMPANION 419200
then
iridiumsbd start -d /dev/ttyS2
mavlink start -d /dev/iridium -b 19200 -m iridium -r 10
fi
if param compare SYS_COMPANION 1921600
then
mavlink start -d $MAVLINK_COMPANION_DEVICE -b 921600 -r 20000
Expand Down
1 change: 1 addition & 0 deletions cmake/configs/nuttx_px4fmu-v2_default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ set(config_module_list
drivers/bst
#drivers/snapdragon_rc_pwm
drivers/lis3mdl
drivers/iridiumsbd

#
# System commands
Expand Down
1 change: 1 addition & 0 deletions cmake/configs/nuttx_px4fmu-v3_default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ set(config_module_list
drivers/hott
drivers/hott/hott_sensors
drivers/hott/hott_telemetry
drivers/iridiumsbd
drivers/l3gd20
drivers/led
drivers/lis3mdl
Expand Down
1 change: 1 addition & 0 deletions cmake/configs/nuttx_px4fmu-v4_default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ set(config_module_list
drivers/bma180
drivers/bmi160
drivers/tap_esc
drivers/iridiumsbd

#
# System commands
Expand Down
1 change: 1 addition & 0 deletions msg/telemetry_status.msg
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ uint8 TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO = 1
uint8 TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET = 2
uint8 TELEMETRY_STATUS_RADIO_TYPE_WIRE = 3
uint8 TELEMETRY_STATUS_RADIO_TYPE_USB = 4
uint8 TELEMETRY_STATUS_RADIO_TYPE_IRIDIUM = 5

uint64 heartbeat_time # Time of last received heartbeat from remote system
uint64 telem_time # Time of last received telemetry status packet, 0 for none
Expand Down
8 changes: 8 additions & 0 deletions src/drivers/drv_iridiumsbd.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#pragma once

#include <stdint.h>
#include <sys/ioctl.h>

#include "board_config.h"

#define IRIDIUMSBD_DEVICE_PATH "/dev/iridium"
45 changes: 45 additions & 0 deletions src/drivers/iridiumsbd/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
############################################################################
#
# Copyright (c) 2016 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.
#
############################################################################
px4_add_module(
MODULE drivers__iridiumsbd
MAIN iridiumsbd
STACK 1024
STACK_MAIN 1024
COMPILE_FLAGS
-Os
SRCS
IridiumSBD.cpp
iridiumsbd_params.c
DEPENDS
platforms__common
)
Loading

0 comments on commit bce7ecb

Please sign in to comment.