mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 21:55:34 +08:00
@@ -4,3 +4,6 @@
|
||||
[submodule "NuttX"]
|
||||
path = NuttX
|
||||
url = git://github.com/PX4/NuttX.git
|
||||
[submodule "uavcan"]
|
||||
path = uavcan
|
||||
url = git://github.com/pavel-kirienko/uavcan.git
|
||||
|
||||
@@ -212,6 +212,9 @@ endif
|
||||
$(NUTTX_SRC):
|
||||
$(Q) ($(PX4_BASE)/Tools/check_submodules.sh)
|
||||
|
||||
$(UAVCAN_DIR):
|
||||
$(Q) (./Tools/check_submodules.sh)
|
||||
|
||||
.PHONY: checksubmodules
|
||||
checksubmodules:
|
||||
$(Q) ($(PX4_BASE)/Tools/check_submodules.sh)
|
||||
|
||||
@@ -0,0 +1,27 @@
|
||||
#!nsh
|
||||
#
|
||||
# F450-sized quadrotor with CAN
|
||||
#
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
sh /etc/init.d/4001_quad_x
|
||||
|
||||
if [ $DO_AUTOCONFIG == yes ]
|
||||
then
|
||||
# TODO REVIEW
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
||||
set OUTPUT_MODE uavcan_esc
|
||||
@@ -136,6 +136,11 @@ then
|
||||
sh /etc/init.d/4011_dji_f450
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4012
|
||||
then
|
||||
sh /etc/init.d/4012_quad_x_can
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 4020
|
||||
then
|
||||
sh /etc/init.d/4020_hk_micro_pcb
|
||||
|
||||
@@ -24,6 +24,11 @@ then
|
||||
else
|
||||
set OUTPUT_DEV /dev/pwm_output
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == uavcan_esc ]
|
||||
then
|
||||
set OUTPUT_DEV /dev/uavcan/esc
|
||||
fi
|
||||
|
||||
if mixer load $OUTPUT_DEV $MIXER_FILE
|
||||
then
|
||||
|
||||
@@ -297,7 +297,17 @@ then
|
||||
# If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output
|
||||
if [ $OUTPUT_MODE != none ]
|
||||
then
|
||||
if [ $OUTPUT_MODE == io ]
|
||||
if [ $OUTPUT_MODE == uavcan_esc ]
|
||||
then
|
||||
if uavcan start 1
|
||||
then
|
||||
echo "CAN UP"
|
||||
else
|
||||
echo "CAN ERR"
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ]
|
||||
then
|
||||
echo "[init] Use PX4IO PWM as primary output"
|
||||
if px4io start
|
||||
|
||||
@@ -53,4 +53,28 @@ else
|
||||
git submodule update;
|
||||
fi
|
||||
|
||||
|
||||
if [ -d uavcan ]
|
||||
then
|
||||
STATUSRETVAL=$(git submodule summary | grep -A20 -i uavcan | grep "<")
|
||||
if [ -z "$STATUSRETVAL" ]
|
||||
then
|
||||
echo "Checked uavcan submodule, correct version found"
|
||||
else
|
||||
echo ""
|
||||
echo ""
|
||||
echo "uavcan sub repo not at correct version. Try 'git submodule update'"
|
||||
echo "or follow instructions on http://pixhawk.org/dev/git/submodules"
|
||||
echo ""
|
||||
echo ""
|
||||
echo "New commits required:"
|
||||
echo "$(git submodule summary)"
|
||||
echo ""
|
||||
exit 1
|
||||
fi
|
||||
else
|
||||
git submodule init
|
||||
git submodule update
|
||||
fi
|
||||
|
||||
exit 0
|
||||
|
||||
@@ -74,6 +74,7 @@ MODULES += modules/commander
|
||||
MODULES += modules/navigator
|
||||
MODULES += modules/mavlink
|
||||
MODULES += modules/gpio_led
|
||||
MODULES += modules/uavcan
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
|
||||
@@ -64,6 +64,7 @@ LDSCRIPT += $(NUTTX_EXPORT_DIR)build/ld.script
|
||||
# Add directories from the NuttX export to the relevant search paths
|
||||
#
|
||||
INCLUDE_DIRS += $(NUTTX_EXPORT_DIR)include \
|
||||
$(NUTTX_EXPORT_DIR)include/cxx \
|
||||
$(NUTTX_EXPORT_DIR)arch/chip \
|
||||
$(NUTTX_EXPORT_DIR)arch/common
|
||||
|
||||
|
||||
@@ -49,6 +49,7 @@ export NUTTX_SRC = $(abspath $(PX4_BASE)/NuttX/nuttx)/
|
||||
export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink/include/mavlink/v1.0)/
|
||||
export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/NuttX/apps)/
|
||||
export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink)/
|
||||
export UAVCAN_DIR = $(abspath $(PX4_BASE)/uavcan)/
|
||||
export ROMFS_SRC = $(abspath $(PX4_BASE)/ROMFS)/
|
||||
export IMAGE_DIR = $(abspath $(PX4_BASE)/Images)/
|
||||
export BUILD_DIR = $(abspath $(PX4_BASE)/Build)/
|
||||
|
||||
@@ -121,7 +121,7 @@ INSTRUMENTATIONDEFINES = $(ARCHINSTRUMENTATIONDEFINES_$(CONFIG_ARCH))
|
||||
# Language-specific flags
|
||||
#
|
||||
ARCHCFLAGS = -std=gnu99
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -fno-threadsafe-statics
|
||||
|
||||
# Generic warnings
|
||||
#
|
||||
|
||||
@@ -0,0 +1 @@
|
||||
./dsdlc_generated/
|
||||
@@ -0,0 +1,138 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 esc_controller.cpp
|
||||
*
|
||||
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
|
||||
*/
|
||||
|
||||
#include "esc_controller.hpp"
|
||||
#include <systemlib/err.h>
|
||||
|
||||
UavcanEscController::UavcanEscController(uavcan::INode &node) :
|
||||
_node(node),
|
||||
_uavcan_pub_raw_cmd(node),
|
||||
_uavcan_sub_status(node),
|
||||
_orb_timer(node)
|
||||
{
|
||||
}
|
||||
|
||||
UavcanEscController::~UavcanEscController()
|
||||
{
|
||||
perf_free(_perfcnt_invalid_input);
|
||||
perf_free(_perfcnt_scaling_error);
|
||||
}
|
||||
|
||||
int UavcanEscController::init()
|
||||
{
|
||||
// ESC status subscription
|
||||
int res = _uavcan_sub_status.start(StatusCbBinder(this, &UavcanEscController::esc_status_sub_cb));
|
||||
if (res < 0)
|
||||
{
|
||||
warnx("ESC status sub failed %i", res);
|
||||
return res;
|
||||
}
|
||||
|
||||
// ESC status will be relayed from UAVCAN bus into ORB at this rate
|
||||
_orb_timer.setCallback(TimerCbBinder(this, &UavcanEscController::orb_pub_timer_cb));
|
||||
_orb_timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / ESC_STATUS_UPDATE_RATE_HZ));
|
||||
|
||||
return res;
|
||||
}
|
||||
|
||||
void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
|
||||
{
|
||||
if ((outputs == nullptr) || (num_outputs > MAX_ESCS)) {
|
||||
perf_count(_perfcnt_invalid_input);
|
||||
return;
|
||||
}
|
||||
|
||||
/*
|
||||
* Rate limiting - we don't want to congest the bus
|
||||
*/
|
||||
const auto timestamp = _node.getMonotonicTime();
|
||||
if ((timestamp - _prev_cmd_pub).toUSec() < (1000000 / MAX_RATE_HZ)) {
|
||||
return;
|
||||
}
|
||||
_prev_cmd_pub = timestamp;
|
||||
|
||||
/*
|
||||
* Fill the command message
|
||||
* If unarmed, we publish an empty message anyway
|
||||
*/
|
||||
uavcan::equipment::esc::RawCommand msg;
|
||||
|
||||
if (_armed) {
|
||||
for (unsigned i = 0; i < num_outputs; i++) {
|
||||
|
||||
float scaled = (outputs[i] + 1.0F) * 0.5F * uavcan::equipment::esc::RawCommand::CMD_MAX;
|
||||
if (scaled < 1.0F) {
|
||||
scaled = 1.0F; // Since we're armed, we don't want to stop it completely
|
||||
}
|
||||
|
||||
if (scaled < uavcan::equipment::esc::RawCommand::CMD_MIN) {
|
||||
scaled = uavcan::equipment::esc::RawCommand::CMD_MIN;
|
||||
perf_count(_perfcnt_scaling_error);
|
||||
} else if (scaled > uavcan::equipment::esc::RawCommand::CMD_MAX) {
|
||||
scaled = uavcan::equipment::esc::RawCommand::CMD_MAX;
|
||||
perf_count(_perfcnt_scaling_error);
|
||||
} else {
|
||||
; // Correct value
|
||||
}
|
||||
|
||||
msg.cmd.push_back(static_cast<unsigned>(scaled));
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Publish the command message to the bus
|
||||
* Note that for a quadrotor it takes one CAN frame
|
||||
*/
|
||||
(void)_uavcan_pub_raw_cmd.broadcast(msg);
|
||||
}
|
||||
|
||||
void UavcanEscController::arm_esc(bool arm)
|
||||
{
|
||||
_armed = arm;
|
||||
}
|
||||
|
||||
void UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status> &msg)
|
||||
{
|
||||
// TODO save status into a local storage; publish to ORB later from orb_pub_timer_cb()
|
||||
}
|
||||
|
||||
void UavcanEscController::orb_pub_timer_cb(const uavcan::TimerEvent&)
|
||||
{
|
||||
// TODO publish to ORB
|
||||
}
|
||||
@@ -0,0 +1,107 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 esc_controller.hpp
|
||||
*
|
||||
* UAVCAN <--> ORB bridge for ESC messages:
|
||||
* uavcan.equipment.esc.RawCommand
|
||||
* uavcan.equipment.esc.RPMCommand
|
||||
* uavcan.equipment.esc.Status
|
||||
*
|
||||
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <uavcan/uavcan.hpp>
|
||||
#include <uavcan/equipment/esc/RawCommand.hpp>
|
||||
#include <uavcan/equipment/esc/Status.hpp>
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
class UavcanEscController
|
||||
{
|
||||
public:
|
||||
UavcanEscController(uavcan::INode& node);
|
||||
~UavcanEscController();
|
||||
|
||||
int init();
|
||||
|
||||
void update_outputs(float *outputs, unsigned num_outputs);
|
||||
|
||||
void arm_esc(bool arm);
|
||||
|
||||
private:
|
||||
/**
|
||||
* ESC status message reception will be reported via this callback.
|
||||
*/
|
||||
void esc_status_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status> &msg);
|
||||
|
||||
/**
|
||||
* ESC status will be published to ORB from this callback (fixed rate).
|
||||
*/
|
||||
void orb_pub_timer_cb(const uavcan::TimerEvent &event);
|
||||
|
||||
|
||||
static constexpr unsigned MAX_RATE_HZ = 100; ///< XXX make this configurable
|
||||
static constexpr unsigned ESC_STATUS_UPDATE_RATE_HZ = 5;
|
||||
static constexpr unsigned MAX_ESCS = uavcan::equipment::esc::RawCommand::FieldTypes::cmd::MaxSize;
|
||||
|
||||
typedef uavcan::MethodBinder<UavcanEscController*,
|
||||
void (UavcanEscController::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status>&)>
|
||||
StatusCbBinder;
|
||||
|
||||
typedef uavcan::MethodBinder<UavcanEscController*, void (UavcanEscController::*)(const uavcan::TimerEvent&)>
|
||||
TimerCbBinder;
|
||||
|
||||
/*
|
||||
* libuavcan related things
|
||||
*/
|
||||
uavcan::MonotonicTime _prev_cmd_pub; ///< rate limiting
|
||||
uavcan::INode &_node;
|
||||
uavcan::Publisher<uavcan::equipment::esc::RawCommand> _uavcan_pub_raw_cmd;
|
||||
uavcan::Subscriber<uavcan::equipment::esc::Status, StatusCbBinder> _uavcan_sub_status;
|
||||
uavcan::TimerEventForwarder<TimerCbBinder> _orb_timer;
|
||||
|
||||
/*
|
||||
* ESC states
|
||||
*/
|
||||
bool _armed = false;
|
||||
uavcan::equipment::esc::Status _states[MAX_ESCS];
|
||||
|
||||
/*
|
||||
* Perf counters
|
||||
*/
|
||||
perf_counter_t _perfcnt_invalid_input = perf_alloc(PC_COUNT, "uavcan_esc_invalid_input");
|
||||
perf_counter_t _perfcnt_scaling_error = perf_alloc(PC_COUNT, "uavcan_esc_scaling_error");
|
||||
};
|
||||
@@ -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);
|
||||
|
||||
// Horizontal position uncertainty
|
||||
const float horizontal_pos_variance = math::max(pos_cov[0], pos_cov[4]);
|
||||
_report.eph = (horizontal_pos_variance > 0) ? sqrtf(horizontal_pos_variance) : -1.0F;
|
||||
|
||||
// Vertical position uncertainty
|
||||
_report.epv = (pos_cov[8] > 0) ? sqrtf(pos_cov[8]) : -1.0F;
|
||||
} else {
|
||||
_report.eph = -1.0F;
|
||||
_report.epv = -1.0F;
|
||||
}
|
||||
|
||||
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));
|
||||
|
||||
} else {
|
||||
_report.s_variance_m_s = -1.0F;
|
||||
_report.c_variance_rad = -1.0F;
|
||||
}
|
||||
|
||||
_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 = uavcan::UtcTime(msg.gnss_timestamp).toUSec(); // Convert to microseconds
|
||||
|
||||
_report.satellites_used = msg.sats_used;
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
}
|
||||
@@ -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
|
||||
|
||||
};
|
||||
@@ -0,0 +1,74 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
||||
# Author: Pavel Kirienko <pavel.kirienko@gmail.com>
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# UAVCAN <--> uORB bridge
|
||||
#
|
||||
|
||||
MODULE_COMMAND = uavcan
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
SRCS += uavcan_main.cpp \
|
||||
uavcan_clock.cpp \
|
||||
esc_controller.cpp \
|
||||
gnss_receiver.cpp
|
||||
|
||||
#
|
||||
# libuavcan
|
||||
#
|
||||
include $(UAVCAN_DIR)/libuavcan/include.mk
|
||||
SRCS += $(LIBUAVCAN_SRC)
|
||||
INCLUDE_DIRS += $(LIBUAVCAN_INC)
|
||||
# Since actual compiler mode is C++11, the library will default to UAVCAN_CPP11, but it will fail to compile
|
||||
# because this platform lacks most of the standard library and STL. Hence we need to force C++03 mode.
|
||||
override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 -DUAVCAN_NO_ASSERTIONS
|
||||
|
||||
#
|
||||
# libuavcan drivers for STM32
|
||||
#
|
||||
include $(UAVCAN_DIR)/libuavcan_drivers/stm32/driver/include.mk
|
||||
SRCS += $(LIBUAVCAN_STM32_SRC)
|
||||
INCLUDE_DIRS += $(LIBUAVCAN_STM32_INC)
|
||||
override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM_IFACES=2
|
||||
|
||||
#
|
||||
# Invoke DSDL compiler
|
||||
# TODO: Add make target for this, or invoke dsdlc manually.
|
||||
# The second option assumes that the generated headers shall be saved
|
||||
# under the version control, which may be undesirable.
|
||||
# The first option requires any Python and the Python Mako library for the sources to be built.
|
||||
#
|
||||
$(info $(shell $(LIBUAVCAN_DSDLC) $(UAVCAN_DSDL_DIR)))
|
||||
INCLUDE_DIRS += dsdlc_generated
|
||||
@@ -0,0 +1,79 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <uavcan_stm32/uavcan_stm32.hpp>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
/**
|
||||
* @file uavcan_clock.cpp
|
||||
*
|
||||
* Implements a clock for the CAN node.
|
||||
*
|
||||
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
|
||||
*/
|
||||
|
||||
namespace uavcan_stm32
|
||||
{
|
||||
namespace clock
|
||||
{
|
||||
|
||||
uavcan::MonotonicTime getMonotonic()
|
||||
{
|
||||
return uavcan::MonotonicTime::fromUSec(hrt_absolute_time());
|
||||
}
|
||||
|
||||
uavcan::UtcTime getUtc()
|
||||
{
|
||||
return uavcan::UtcTime();
|
||||
}
|
||||
|
||||
void adjustUtc(uavcan::UtcDuration adjustment)
|
||||
{
|
||||
(void)adjustment;
|
||||
}
|
||||
|
||||
uavcan::uint64_t getUtcUSecFromCanInterrupt()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
} // namespace clock
|
||||
|
||||
SystemClock &SystemClock::instance()
|
||||
{
|
||||
static SystemClock inst;
|
||||
return inst;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,123 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <uavcan_stm32/uavcan_stm32.hpp>
|
||||
#include <drivers/device/device.h>
|
||||
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/actuator_outputs.h>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
|
||||
#include "esc_controller.hpp"
|
||||
#include "gnss_receiver.hpp"
|
||||
|
||||
/**
|
||||
* @file uavcan_main.hpp
|
||||
*
|
||||
* Defines basic functinality of UAVCAN node.
|
||||
*
|
||||
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
|
||||
*/
|
||||
|
||||
#define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 4
|
||||
#define UAVCAN_DEVICE_PATH "/dev/uavcan/esc"
|
||||
|
||||
/**
|
||||
* A UAVCAN node.
|
||||
*/
|
||||
class UavcanNode : public device::CDev
|
||||
{
|
||||
static constexpr unsigned MemPoolSize = 10752;
|
||||
static constexpr unsigned RxQueueLenPerIface = 64;
|
||||
static constexpr unsigned StackSize = 3000;
|
||||
|
||||
public:
|
||||
typedef uavcan::Node<MemPoolSize> Node;
|
||||
typedef uavcan_stm32::CanInitHelper<RxQueueLenPerIface> CanInitHelper;
|
||||
|
||||
UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock);
|
||||
|
||||
virtual ~UavcanNode();
|
||||
|
||||
virtual int ioctl(file *filp, int cmd, unsigned long arg);
|
||||
|
||||
static int start(uavcan::NodeID node_id, uint32_t bitrate);
|
||||
|
||||
Node& getNode() { return _node; }
|
||||
|
||||
static int control_callback(uintptr_t handle,
|
||||
uint8_t control_group,
|
||||
uint8_t control_index,
|
||||
float &input);
|
||||
|
||||
void subscribe();
|
||||
|
||||
int teardown();
|
||||
int arm_actuators(bool arm);
|
||||
|
||||
void print_info();
|
||||
|
||||
static UavcanNode* instance() { return _instance; }
|
||||
|
||||
private:
|
||||
int init(uavcan::NodeID node_id);
|
||||
void node_spin_once();
|
||||
int run();
|
||||
|
||||
int _task = -1; ///< handle to the OS task
|
||||
bool _task_should_exit = false; ///< flag to indicate to tear down the CAN driver
|
||||
int _armed_sub = -1; ///< uORB subscription of the arming status
|
||||
actuator_armed_s _armed; ///< the arming request of the system
|
||||
bool _is_armed = false; ///< the arming status of the actuators on the bus
|
||||
|
||||
unsigned _output_count = 0; ///< number of actuators currently available
|
||||
|
||||
static UavcanNode *_instance; ///< singleton pointer
|
||||
Node _node; ///< library instance
|
||||
UavcanEscController _esc_controller;
|
||||
UavcanGnssReceiver _gnss_receiver;
|
||||
|
||||
MixerGroup *_mixers = nullptr;
|
||||
|
||||
uint32_t _groups_required = 0;
|
||||
uint32_t _groups_subscribed = 0;
|
||||
int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
||||
actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
||||
orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
||||
pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN + 1] = {}; ///< +1 for /dev/uavcan/busevent
|
||||
unsigned _poll_fds_num = 0;
|
||||
};
|
||||
Submodule
+1
Submodule uavcan added at dca2611c31
Reference in New Issue
Block a user