Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
.cache
*.dSYM
*.o
*.gch
Expand Down
5 changes: 5 additions & 0 deletions .vscode/cmake-variants.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,11 @@ CONFIG:
buildType: RelWithDebInfo
settings:
CONFIG: px4_sitl_default
px4_sitl_evl4:
short: px4_sitl_evl4
buildType: RelWithDebInfo
settings:
CONFIG: px4_sitl_evl4
px4_sitl_nolockstep:
short: px4_sitl_nolockstep
buildType: RelWithDebInfo
Expand Down
6 changes: 6 additions & 0 deletions Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,12 @@ menu "Toolchain"
help
Board Platform is running the Linux operating system

config BOARD_EVL4_TARGET
bool "EVL4 OS Target"
depends on PLATFORM_POSIX
help
Board Platform is running the EVL4 operating system

config BOARD_TOOLCHAIN
string "Toolchain"
default ""
Expand Down
8 changes: 4 additions & 4 deletions ROMFS/px4fmu_common/init.d-posix/px4-rc.mavlink
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ udp_onboard_gimbal_port_remote=$((13280+px4_instance))
udp_gcs_port_local=$((18570+px4_instance))

# GCS link
mavlink start -x -u $udp_gcs_port_local -r 4000000 -f
mavlink start -x -u $udp_gcs_port_local -r 4000000 -f -p -t 10.29.240.226
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u $udp_gcs_port_local
mavlink stream -r 50 -s LOCAL_POSITION_NED -u $udp_gcs_port_local
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u $udp_gcs_port_local
Expand All @@ -23,13 +23,13 @@ mavlink stream -r 20 -s RC_CHANNELS -u $udp_gcs_port_local
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u $udp_gcs_port_local

# API/Offboard link
mavlink start -x -u $udp_offboard_port_local -r 4000000 -f -m onboard -o $udp_offboard_port_remote
mavlink start -x -u $udp_offboard_port_local -r 4000000 -f -m onboard -o $udp_offboard_port_remote -p -t 10.29.240.226

# Onboard link to camera
mavlink start -x -u $udp_onboard_payload_port_local -r 4000 -f -m onboard -o $udp_onboard_payload_port_remote
mavlink start -x -u $udp_onboard_payload_port_local -r 4000 -f -m onboard -o $udp_onboard_payload_port_remote -p -t 10.29.240.226

# Onboard link to gimbal
mavlink start -x -u $udp_onboard_gimbal_port_local -r 400000 -f -m gimbal -o $udp_onboard_gimbal_port_remote
mavlink start -x -u $udp_onboard_gimbal_port_local -r 400000 -f -m gimbal -o $udp_onboard_gimbal_port_remote -p -t 10.29.240.226

# To display for SIH sitl
if [ "$PX4_SIMULATOR" = "sihsim" ]; then
Expand Down
4 changes: 2 additions & 2 deletions ROMFS/px4fmu_common/init.d-posix/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
# Un comment and use set +e to ignore and set -e to enable 'exit on error control'
set +e
# Un comment the line below to help debug scripts by printing a trace of the script commands
#set -x
set -x

# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
Expand Down Expand Up @@ -204,7 +204,7 @@ fi
# Autostart ID
autostart_file=''
# shellcheck disable=SC2231
for f in ${R}etc/init.d-posix/airframes/"$(param show -q SYS_AUTOSTART)"_*
for f in ${R}etc/init.d-posix/airframes/"${SYS_AUTOSTART}"_*
do
filename=$(basename "$f")
case "$filename" in
Expand Down
87 changes: 87 additions & 0 deletions boards/px4/sitl/evl4.px4board
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
CONFIG_PLATFORM_POSIX=y
CONFIG_BOARD_NOLOCKSTEP=y
CONFIG_BOARD_EVL4_TARGET=y
CONFIG_BOARD_TESTING=y
CONFIG_BOARD_ETHERNET=y
CONFIG_BOARD_ROOT_PATH="."
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_MODULES_AIRSHIP_ATT_CONTROL=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_EKF2_VERBOSE_STATUS=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL=y
CONFIG_FIGURE_OF_EIGHT=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MAVLINK_DIALECT="development"
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_MODULES_PAYLOAD_DELIVERER=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_REPLAY=y
CONFIG_MODULES_ROVER_ACKERMANN=y
CONFIG_MODULES_ROVER_DIFFERENTIAL=y
CONFIG_MODULES_ROVER_MECANUM=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_COMMON_SIMULATION=y
CONFIG_MODULES_SIMULATION_GZ_MSGS=y
CONFIG_MODULES_SIMULATION_GZ_BRIDGE=y
CONFIG_MODULES_SIMULATION_GZ_PLUGINS=y
CONFIG_MODULES_SIMULATION_SENSOR_AGP_SIM=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DYN=y
CONFIG_SYSTEMCMDS_FAILURE=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SHUTDOWN=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_DYN_HELLO=y
CONFIG_EXAMPLES_FAKE_GPS=y
CONFIG_EXAMPLES_FAKE_IMU=y
CONFIG_EXAMPLES_FAKE_MAGNETOMETER=y
CONFIG_EXAMPLES_HELLO=y
CONFIG_EXAMPLES_PX4_MAVLINK_DEBUG=y
CONFIG_EXAMPLES_PX4_SIMPLE_APP=y
CONFIG_EXAMPLES_WORK_ITEM=y
CONFIG_MODULES_SPACECRAFT=n
1 change: 1 addition & 0 deletions boards/px4/sitl/test.px4board
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
CONFIG_BOARD_NOLOCKSTEP=y
CONFIG_BOARD_EVL4_TARGET=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL=y
4 changes: 4 additions & 0 deletions cmake/kconfig.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -390,6 +390,10 @@ if(EXISTS ${BOARD_DEFCONFIG})
add_definitions( "-D__PX4_LINUX" )
endif()

if(EVL4_TARGET)
add_definitions( "-D__PX4_EVL4" )
endif()

if(LOCKSTEP)
set(ENABLE_LOCKSTEP_SCHEDULER yes)
endif()
Expand Down
73 changes: 73 additions & 0 deletions platforms/common/include/px4_platform_common/evl_helper.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
/****************************************************************************
*
* Copyright (c) 2025 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 <string.h>
#include <stdlib.h>
#include <evl/proxy.h>
#include <evl/sched.h>
#include <evl/thread.h>

#define __stringify_1(x...) #x
#define __stringify(x...) __stringify_1(x)
#define evl_warn_failed(__fmt, __args...) \
evl_eprintf("%s:%d: FAILED: " __fmt "\n", \
__FILE__, __LINE__, ##__args)

#define __Tcall(__ret, __call) \
({ \
(__ret) = (__call); \
if (__ret < 0) { \
evl_warn_failed("%s (=%s)", \
__stringify(__call), \
strerror(-(__ret))); \
} \
(__ret) >= 0; \
})

#define __Tcall_assert(__ret, __call) \
do { \
if (!__Tcall(__ret, __call)) \
exit(__ret); \
} while (0)

// Attach to evl core and set thread name, scheduling policy and priority.
#define __attach_and_setsched(__policy, __prio, __fmt, __args...) \
do { \
int __ret; \
__Tcall_assert(__ret, evl_attach_self(__fmt, ##__args)); \
struct evl_sched_attrs __attrs; \
__attrs.sched_policy = __policy; \
__attrs.sched_priority = __prio; \
__Tcall_assert(__ret, evl_set_schedattr(__ret, &__attrs)); \
} while (0)
12 changes: 12 additions & 0 deletions platforms/common/include/px4_platform_common/module.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,11 @@
* there is only a single global mutex. This sounds bad, but we actually don't expect
* contention here, as module startup is sequential.
*/
#ifndef __PX4_EVL4
extern pthread_mutex_t px4_modules_mutex;
#else
extern struct evl_mutex px4_modules_mutex;
#endif

/**
* @class ModuleBase
Expand Down Expand Up @@ -405,15 +409,23 @@ class ModuleBase
*/
static void lock_module()
{
#ifndef __PX4_EVL4
pthread_mutex_lock(&px4_modules_mutex);
#else
evl_lock_mutex(&px4_modules_mutex);
#endif
}

/**
* @brief unlock_module Mutex to unlock the module thread.
*/
static void unlock_module()
{
#ifndef __PX4_EVL4
pthread_mutex_unlock(&px4_modules_mutex);
#else
evl_unlock_mutex(&px4_modules_mutex);
#endif
}

/** @var _task_should_exit Boolean flag to indicate if the task should exit. */
Expand Down
14 changes: 14 additions & 0 deletions platforms/common/include/px4_platform_common/posix.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,16 @@ typedef struct {
/* Required for PX4 compatibility */
px4_sem_t *sem; /* Pointer to semaphore used to post output event */
void *priv; /* For use by drivers */
#ifdef __PX4_EVL4
/* Store the evl pollfd, all fds in a array have the same efd
we can just store it at the head of array
*/
int efd;
/* Store the result pollset, all fds in a array have the same pollset
we can just store it at the head of array
*/
struct evl_poll_event *pollset;
#endif
} px4_pollfd_struct_t;

#ifndef POLLIN
Expand All @@ -118,6 +128,10 @@ __EXPORT int px4_close(int fd);
__EXPORT ssize_t px4_read(int fd, void *buffer, size_t buflen);
__EXPORT ssize_t px4_write(int fd, const void *buffer, size_t buflen);
__EXPORT int px4_ioctl(int fd, int cmd, unsigned long arg);
#ifdef __PX4_EVL4
__EXPORT int px4_poll_init(px4_pollfd_struct_t *fds, unsigned int nfds);
__EXPORT int px4_poll_destory(px4_pollfd_struct_t *fds, unsigned int nfds);
#endif
__EXPORT int px4_poll(px4_pollfd_struct_t *fds, unsigned int nfds, int timeout);
__EXPORT int px4_access(const char *pathname, int mode);
__EXPORT px4_task_t px4_getpid(void);
Expand Down
8 changes: 8 additions & 0 deletions platforms/common/include/px4_platform_common/sem.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,10 @@

#include <semaphore.h>

#if defined(__PX4_EVL4)
#include <evl/sem.h>
#endif

#if !defined(__PX4_NUTTX)
/* Values for protocol attribute */

Expand All @@ -54,11 +58,15 @@

__BEGIN_DECLS

#if defined(__PX4_EVL4)
typedef struct evl_sem px4_sem_t;
#else
typedef struct {
pthread_mutex_t lock;
pthread_cond_t wait;
int value;
} px4_sem_t;
#endif

__EXPORT int px4_sem_init(px4_sem_t *s, int pshared, unsigned value);
__EXPORT int px4_sem_setprotocol(px4_sem_t *s, int protocol);
Expand Down
12 changes: 12 additions & 0 deletions platforms/common/include/px4_platform_common/time.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,11 @@
#include <time.h>
#include <pthread.h>

#if defined(__PX4_EVL4)
#include <evl/mutex.h>
#include <evl/event.h>
#endif

#if defined(__PX4_POSIX)
__BEGIN_DECLS
__EXPORT int px4_clock_gettime(clockid_t clk_id, struct timespec *tp);
Expand All @@ -30,9 +35,16 @@ __END_DECLS
__BEGIN_DECLS
__EXPORT int px4_usleep(useconds_t usec);
__EXPORT unsigned int px4_sleep(unsigned int seconds);

#if defined(__PX4_EVL4)
__EXPORT int px4_pthread_cond_timedwait(struct evl_event *cond,
struct evl_mutex *mutex,
const struct timespec *abstime);
#else
__EXPORT int px4_pthread_cond_timedwait(pthread_cond_t *cond,
pthread_mutex_t *mutex,
const struct timespec *abstime);
#endif
__END_DECLS

#else
Expand Down
6 changes: 6 additions & 0 deletions platforms/common/module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,13 @@
#include <px4_platform_common/defines.h>
#include <px4_platform_common/log.h>

#ifndef __PX4_EVL4
pthread_mutex_t px4_modules_mutex = PTHREAD_MUTEX_INITIALIZER;
#else
#include <evl/mutex.h>
struct evl_mutex px4_modules_mutex = EVL_MUTEX_INITIALIZER("/modules_mutex", EVL_CLOCK_MONOTONIC, 0,
EVL_MUTEX_NORMAL | EVL_CLONE_PUBLIC);
#endif

#ifndef __PX4_NUTTX

Expand Down
Loading
Loading