Compare commits

...

6 Commits

7 changed files with 30 additions and 9 deletions

View File

@ -10,7 +10,6 @@ CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
CONFIG_DRIVERS_QSHELL_QURT=y
CONFIG_DRIVERS_VOXL2_IO=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_EKF2=y
@ -28,4 +27,5 @@ CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_ORB_COMMUNICATOR=y

View File

@ -49,6 +49,6 @@ add_subdirectory(${PX4_BOARD_DIR}/src/drivers/rc_controller)
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/mavlink_rc_in)
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/spektrum_rc)
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/ghst_rc)
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_hitl)
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_hitl)
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_sbus)
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/elrs_led)

View File

@ -989,10 +989,10 @@ handle_message_hil_gps_dsp(mavlink_message_t *msg)
gps.device_id = device_id.devid;
gps.lat = hil_gps.lat;
gps.lon = hil_gps.lon;
gps.alt = hil_gps.alt;
gps.alt_ellipsoid = hil_gps.alt;
gps.latitude_deg = hil_gps.lat;
gps.longitude_deg = hil_gps.lon;
gps.altitude_msl_m = hil_gps.alt;
gps.altitude_ellipsoid_m = hil_gps.alt;
gps.s_variance_m_s = 0.25f;
gps.c_variance_rad = 0.5f;

View File

@ -48,6 +48,8 @@
#include <board_config.h>
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
#include <inttypes.h>
#include <stdbool.h>
#include <syslog.h>
@ -57,7 +59,6 @@
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
typedef struct {
hw_base_id_t hw_base_id; /* The ID of the Base */

View File

@ -40,15 +40,34 @@
#include <px4_platform_common/px4_work_queue/WorkQueueManager.hpp>
#include <uORB/uORB.h>
#if defined(CONFIG_MODULES_MUORB_APPS)
extern "C" { int muorb_init(); }
#endif
int px4_platform_init(void)
{
hrt_init();
px4::WorkQueueManagerStart();
// MUORB has slightly different startup requirements
#if defined(CONFIG_MODULES_MUORB_APPS)
//Put sleeper in here to allow wq to finish initializing before param_init is called
usleep(10000);
uorb_start();
muorb_init();
// Give muorb some time to setup the DSP
usleep(100000);
param_init();
#else
param_init();
uorb_start();
#endif
px4_log_initialize();

View File

@ -45,6 +45,7 @@ px4_add_module(
voxl2_io.cpp
voxl2_io.hpp
DEPENDS
rc
px4_work_queue
mixer_module
MODULE_CONFIG

View File

@ -275,10 +275,10 @@ int px4muorb_orb_initialize(fc_func_ptrs *func_ptrs, int32_t clock_offset_us)
uORB::Manager::get_instance()->set_uorb_communicator(
uORB::ProtobufChannel::GetInstance());
param_init();
px4::WorkQueueManagerStart();
param_init();
uORB::ProtobufChannel::GetInstance()->RegisterSendHandler(muorb_func_ptrs.topic_data_func_ptr);
// Configure the I2C driver function pointers