fake_ev: add module that publishes fake ev data based on GNSS

This commit is contained in:
bresch 2023-04-28 14:55:49 +02:00
parent 3c9108e11e
commit 704bd22bc1
5 changed files with 404 additions and 0 deletions

View File

@ -0,0 +1,45 @@
############################################################################
#
# Copyright (c) 2023 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 modules__fake_ev
MAIN fake_ev
COMPILE_FLAGS
${MAX_CUSTOM_OPT_LEVEL}
SRCS
fake_ev.cpp
fake_ev.hpp
DEPENDS
px4_work_queue
mathlib
)

View File

@ -0,0 +1,12 @@
menuconfig MODULES_FAKE_EV
bool "fake_ev"
default y
---help---
Enable fake external vision publisher
menuconfig USER_FAKE_EV
bool "fake_ev running as userspace module"
default y
depends on BOARD_PROTECTED && MODULES_FAKE_EV
---help---
Put fake_ev in userspace memory

View File

@ -0,0 +1,199 @@
/****************************************************************************
*
* Copyright (c) 2023 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 fake_ev.cpp
*/
#include "fake_ev.hpp"
#include <mathlib/mathlib.h>
FakeEV::FakeEV() :
ModuleParams(nullptr),
WorkItem(MODULE_NAME, px4::wq_configurations::lp_default)
{
updateParams();
}
FakeEV::~FakeEV()
{
perf_free(_cycle_perf);
}
bool FakeEV::init()
{
if (!_vehicle_gps_position_sub.registerCallback()) {
PX4_ERR("callback registration failed");
return false;
}
return true;
}
void FakeEV::updateParams()
{
ModuleParams::updateParams();
}
void FakeEV::Run()
{
if (should_exit()) {
_vehicle_gps_position_sub.unregisterCallback();
exit_and_cleanup();
return;
}
if (!_vehicle_gps_position_sub.updated()) {
return;
}
perf_begin(_cycle_perf);
sensor_gps_s gps{};
if (_vehicle_gps_position_sub.copy(&gps)) {
vehicle_odometry_s odom = gpsToOdom(gps);
_vehicle_visual_odometry_pub.publish(odom);
}
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// update parameters from storage
updateParams();
}
perf_end(_cycle_perf);
}
vehicle_odometry_s FakeEV::gpsToOdom(const sensor_gps_s &gps)
{
vehicle_odometry_s odom{vehicle_odometry_empty};
/* odom.timestamp_sample = gps.timestamp_sample; */ // gps timestamp_sample isn't set in SITL
odom.timestamp_sample = gps.timestamp;
if (gps.fix_type >= 3) {
if (PX4_ISFINITE(_alt_ref)) {
const matrix::Vector2f hpos = _pos_ref.project(gps.lat / 1.0e7, gps.lon / 1.0e7);
const float vpos = (float)gps.alt * 1e-3f - _alt_ref;
matrix::Vector3f(hpos(0), hpos(1), vpos).copyTo(odom.position);
const float hvar = std::pow(gps.eph, 2.f);
const float vvar = std::pow(gps.epv, 2.f);
matrix::Vector3f(hvar, hvar, vvar).copyTo(odom.position_variance);
odom.pose_frame = vehicle_odometry_s::POSE_FRAME_NED;
} else {
_pos_ref.initReference(gps.lat / 1.0e7, gps.lon / 1.0e7, gps.timestamp);
_alt_ref = (float)gps.alt * 1e-3f;
}
}
if (gps.vel_ned_valid) {
matrix::Vector3f(gps.vel_n_m_s, gps.vel_e_m_s, gps.vel_d_m_s).copyTo(odom.velocity);
matrix::Vector3f vel_var;
vel_var.setAll(std::pow(gps.s_variance_m_s, 2.f));
vel_var.copyTo(odom.velocity_variance);
odom.velocity_frame = vehicle_odometry_s::VELOCITY_FRAME_NED;
}
odom.timestamp = hrt_absolute_time();
return odom;
}
int FakeEV::task_spawn(int argc, char *argv[])
{
FakeEV *instance = new FakeEV();
if (instance) {
_object.store(instance);
_task_id = task_id_is_work_queue;
if (instance->init()) {
return PX4_OK;
}
} else {
PX4_ERR("alloc failed");
}
delete instance;
_object.store(nullptr);
_task_id = -1;
return PX4_ERROR;
}
int FakeEV::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
int FakeEV::print_status()
{
perf_print_counter(_cycle_perf);
return 0;
}
int FakeEV::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("fake_ev", "driver");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}
extern "C" __EXPORT int fake_ev_main(int argc, char *argv[])
{
return FakeEV::main(argc, argv);
}

View File

@ -0,0 +1,112 @@
/****************************************************************************
*
* Copyright (c) 2023 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 fake_ev.hpp
*/
#pragma once
#include <drivers/drv_hrt.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/px4_work_queue/WorkItem.hpp>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/sensor_gps.h>
#include <uORB/topics/vehicle_odometry.h>
using namespace time_literals;
class FakeEV : public ModuleBase<FakeEV>, public ModuleParams,
public px4::WorkItem
{
public:
FakeEV();
~FakeEV() override;
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static int custom_command(int argc, char *argv[]);
/** @see ModuleBase */
static int print_usage(const char *reason = nullptr);
bool init();
/** @see ModuleBase::print_status() */
int print_status() override;
private:
static constexpr vehicle_odometry_s vehicle_odometry_empty {
.timestamp = 0,
.timestamp_sample = 0,
.position = {NAN, NAN, NAN},
.q = {NAN, NAN, NAN, NAN},
.velocity = {NAN, NAN, NAN},
.angular_velocity = {NAN, NAN, NAN},
.position_variance = {NAN, NAN, NAN},
.orientation_variance = {NAN, NAN, NAN},
.velocity_variance = {NAN, NAN, NAN},
.pose_frame = vehicle_odometry_s::POSE_FRAME_UNKNOWN,
.velocity_frame = vehicle_odometry_s::VELOCITY_FRAME_UNKNOWN,
.reset_counter = 0,
.quality = 0
};
void Run() override;
void updateParams() override;
vehicle_odometry_s gpsToOdom(const sensor_gps_s &gps);
uORB::Publication<vehicle_odometry_s> _vehicle_visual_odometry_pub{ORB_ID(vehicle_visual_odometry)};
uORB::SubscriptionCallbackWorkItem _vehicle_gps_position_sub{this, ORB_ID(vehicle_gps_position)};
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
hrt_abstime _timestamp_last{0};
MapProjection _pos_ref{}; // Contains WGS-84 position latitude and longitude
float _alt_ref{NAN};
perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")};
};

View File

@ -0,0 +1,36 @@
/****************************************************************************
*
* Copyright (c) 2023 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 fake_ev_params.c
*/