aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorPavel Kirienko <pavel.kirienko@gmail.com>2014-07-03 22:39:52 +0400
committerPavel Kirienko <pavel.kirienko@gmail.com>2014-07-03 22:39:52 +0400
commitee5dfadb5da07d55fd60b88f2db8926b8503c3c6 (patch)
treedd5a9ebd9d2bdc79e6ef252d093c068bd02aa0d8 /src
parentc4d40b8d284c20829ab84599be7790fdbeaa01fe (diff)
parentc6c33142ceb6bf59b8c9b8e32e94ae5ea7959dbd (diff)
downloadpx4-firmware-ee5dfadb5da07d55fd60b88f2db8926b8503c3c6.tar.gz
px4-firmware-ee5dfadb5da07d55fd60b88f2db8926b8503c3c6.tar.bz2
px4-firmware-ee5dfadb5da07d55fd60b88f2db8926b8503c3c6.zip
Merge pull request #1111 from achambers16/uavcan_gnss
uavcan: bridge uavcan->uorb for gnss msgs
Diffstat (limited to 'src')
-rw-r--r--src/modules/uavcan/gnss_receiver.cpp153
-rw-r--r--src/modules/uavcan/gnss_receiver.hpp84
-rw-r--r--src/modules/uavcan/module.mk3
-rw-r--r--src/modules/uavcan/uavcan_main.cpp7
-rw-r--r--src/modules/uavcan/uavcan_main.hpp2
5 files changed, 247 insertions, 2 deletions
diff --git a/src/modules/uavcan/gnss_receiver.cpp b/src/modules/uavcan/gnss_receiver.cpp
new file mode 100644
index 000000000..3e98bdf14
--- /dev/null
+++ b/src/modules/uavcan/gnss_receiver.cpp
@@ -0,0 +1,153 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file gnss_receiver.cpp
+ *
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ * @author Andrew Chambers <achamber@gmail.com>
+ *
+ */
+
+#include "gnss_receiver.hpp"
+#include <systemlib/err.h>
+#include <mathlib/mathlib.h>
+
+#define MM_PER_CM 10 // Millimeters per centimeter
+
+UavcanGnssReceiver::UavcanGnssReceiver(uavcan::INode &node) :
+_node(node),
+_uavcan_sub_status(node),
+_report_pub(-1)
+{
+}
+
+int UavcanGnssReceiver::init()
+{
+ int res = -1;
+
+ // GNSS fix subscription
+ res = _uavcan_sub_status.start(FixCbBinder(this, &UavcanGnssReceiver::gnss_fix_sub_cb));
+ if (res < 0)
+ {
+ warnx("GNSS fix sub failed %i", res);
+ return res;
+ }
+
+ // Clear the uORB GPS report
+ memset(&_report, 0, sizeof(_report));
+
+ return res;
+}
+
+void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix> &msg)
+{
+ _report.timestamp_position = hrt_absolute_time();
+ _report.lat = msg.lat_1e7;
+ _report.lon = msg.lon_1e7;
+ _report.alt = msg.alt_1e2 * MM_PER_CM; // Convert from centimeter (1e2) to millimeters (1e3)
+
+ _report.timestamp_variance = _report.timestamp_position;
+
+
+ // Check if the msg contains valid covariance information
+ const bool valid_position_covariance = !msg.position_covariance.empty();
+ const bool valid_velocity_covariance = !msg.velocity_covariance.empty();
+
+ if (valid_position_covariance) {
+ float pos_cov[9];
+ msg.position_covariance.unpackSquareMatrix(pos_cov);
+ _report.p_variance_m = math::max(pos_cov[0], pos_cov[4]);
+ _report.eph_m = sqrtf(_report.p_variance_m);
+ } else {
+ _report.p_variance_m = -1.0;
+ _report.eph_m = -1.0;
+ }
+
+ if (valid_velocity_covariance) {
+ float vel_cov[9];
+ msg.velocity_covariance.unpackSquareMatrix(vel_cov);
+ _report.s_variance_m_s = math::max(math::max(vel_cov[0], vel_cov[4]), vel_cov[8]);
+
+ /* There is a nonlinear relationship between the velocity vector and the heading.
+ * Use Jacobian to transform velocity covariance to heading covariance
+ *
+ * Nonlinear equation:
+ * heading = atan2(vel_e_m_s, vel_n_m_s)
+ * For math, see http://en.wikipedia.org/wiki/Atan2#Derivative
+ *
+ * To calculate the variance of heading from the variance of velocity,
+ * cov(heading) = J(velocity)*cov(velocity)*J(velocity)^T
+ */
+ float vel_n = msg.ned_velocity[0];
+ float vel_e = msg.ned_velocity[1];
+ float vel_n_sq = vel_n * vel_n;
+ float vel_e_sq = vel_e * vel_e;
+ _report.c_variance_rad =
+ (vel_e_sq * vel_cov[0] +
+ -2 * vel_n * vel_e * vel_cov[1] + // Covariance matrix is symmetric
+ vel_n_sq* vel_cov[4]) / ((vel_n_sq + vel_e_sq) * (vel_n_sq + vel_e_sq));
+
+ _report.epv_m = sqrtf(msg.position_covariance[8]);
+
+ } else {
+ _report.s_variance_m_s = -1.0;
+ _report.c_variance_rad = -1.0;
+ _report.epv_m = -1.0;
+ }
+
+ _report.fix_type = msg.status;
+
+ _report.timestamp_velocity = _report.timestamp_position;
+ _report.vel_n_m_s = msg.ned_velocity[0];
+ _report.vel_e_m_s = msg.ned_velocity[1];
+ _report.vel_d_m_s = msg.ned_velocity[2];
+ _report.vel_m_s = sqrtf(_report.vel_n_m_s * _report.vel_n_m_s + _report.vel_e_m_s * _report.vel_e_m_s + _report.vel_d_m_s * _report.vel_d_m_s);
+ _report.cog_rad = atan2f(_report.vel_e_m_s, _report.vel_n_m_s);
+ _report.vel_ned_valid = true;
+
+ _report.timestamp_time = _report.timestamp_position;
+ _report.time_gps_usec = msg.timestamp.husec * msg.timestamp.USEC_PER_LSB; // Convert to microseconds
+
+ _report.timestamp_satellites = _report.timestamp_position;
+ _report.satellites_visible = msg.sats_used;
+ _report.satellite_info_available = 0; // Set to 0 for no info available
+
+ if (_report_pub > 0) {
+ orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+
+ } else {
+ _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
+ }
+
+}
diff --git a/src/modules/uavcan/gnss_receiver.hpp b/src/modules/uavcan/gnss_receiver.hpp
new file mode 100644
index 000000000..18df8da2f
--- /dev/null
+++ b/src/modules/uavcan/gnss_receiver.hpp
@@ -0,0 +1,84 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file gnss_receiver.hpp
+ *
+ * UAVCAN --> ORB bridge for GNSS messages:
+ * uavcan.equipment.gnss.Fix
+ *
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ * @author Andrew Chambers <achamber@gmail.com>
+ */
+
+#pragma once
+
+#include <drivers/drv_hrt.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_gps_position.h>
+
+#include <uavcan/uavcan.hpp>
+#include <uavcan/equipment/gnss/Fix.hpp>
+
+class UavcanGnssReceiver
+{
+public:
+ UavcanGnssReceiver(uavcan::INode& node);
+
+ int init();
+
+private:
+ /**
+ * GNSS fix message will be reported via this callback.
+ */
+ void gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix> &msg);
+
+
+ typedef uavcan::MethodBinder<UavcanGnssReceiver*,
+ void (UavcanGnssReceiver::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix>&)>
+ FixCbBinder;
+
+ /*
+ * libuavcan related things
+ */
+ uavcan::INode &_node;
+ uavcan::Subscriber<uavcan::equipment::gnss::Fix, FixCbBinder> _uavcan_sub_status;
+
+ /*
+ * uORB
+ */
+ struct vehicle_gps_position_s _report; ///< uORB topic for gnss position
+ orb_advert_t _report_pub; ///< uORB pub for gnss position
+
+};
diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk
index 5ac7019e3..2c75944d4 100644
--- a/src/modules/uavcan/module.mk
+++ b/src/modules/uavcan/module.mk
@@ -42,7 +42,8 @@ MAXOPTIMIZATION = -Os
SRCS += uavcan_main.cpp \
uavcan_clock.cpp \
- esc_controller.cpp
+ esc_controller.cpp \
+ gnss_receiver.cpp
#
# libuavcan
diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp
index ab687a6b9..5bc437670 100644
--- a/src/modules/uavcan/uavcan_main.cpp
+++ b/src/modules/uavcan/uavcan_main.cpp
@@ -63,7 +63,8 @@ UavcanNode *UavcanNode::_instance;
UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) :
CDev("uavcan", UAVCAN_DEVICE_PATH),
_node(can_driver, system_clock),
- _esc_controller(_node)
+ _esc_controller(_node),
+ _gnss_receiver(_node)
{
_control_topics[0] = ORB_ID(actuator_controls_0);
_control_topics[1] = ORB_ID(actuator_controls_1);
@@ -186,6 +187,10 @@ int UavcanNode::init(uavcan::NodeID node_id)
if (ret < 0)
return ret;
+ ret = _gnss_receiver.init();
+ if (ret < 0)
+ return ret;
+
uavcan::protocol::SoftwareVersion swver;
swver.major = 12; // TODO fill version info
swver.minor = 34;
diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp
index 751a94a8a..443525379 100644
--- a/src/modules/uavcan/uavcan_main.hpp
+++ b/src/modules/uavcan/uavcan_main.hpp
@@ -43,6 +43,7 @@
#include <uORB/topics/actuator_armed.h>
#include "esc_controller.hpp"
+#include "gnss_receiver.hpp"
/**
* @file uavcan_main.hpp
@@ -108,6 +109,7 @@ private:
static UavcanNode *_instance; ///< singleton pointer
Node _node; ///< library instance
UavcanEscController _esc_controller;
+ UavcanGnssReceiver _gnss_receiver;
MixerGroup *_mixers = nullptr;