forked from Archive/PX4-Autopilot
merge px4_sitl_ign into px4_sitl_default (#20188)
- for convenience merge px4_sitl_ign into px4_sitl_default, but allow simulator_ignition_bridge to quietly skip inclusion if ignition-transport isn't available - simulator_ignition_bridge only try setting the system clock in lockstep builds - this simplifies usage and CI system dependencies
This commit is contained in:
parent
34d8bd7988
commit
b8fb5dfa51
|
@ -6,11 +6,6 @@ CONFIG:
|
|||
buildType: RelWithDebInfo
|
||||
settings:
|
||||
CONFIG: px4_sitl_default
|
||||
px4_sitl_ign:
|
||||
short: px4_sitl_ign
|
||||
buildType: RelWithDebInfo
|
||||
settings:
|
||||
CONFIG: px4_sitl_ign
|
||||
px4_sitl_rtps:
|
||||
short: px4_sitl_rtps
|
||||
buildType: RelWithDebInfo
|
||||
|
|
|
@ -56,15 +56,17 @@
|
|||
"options": {
|
||||
"cwd": "${workspaceFolder}/Tools/simulation/jmavsim/jMAVSim"
|
||||
},
|
||||
"problemMatcher": [],
|
||||
"presentation":{
|
||||
"presentation": {
|
||||
"echo": true,
|
||||
"reveal": "never",
|
||||
"revealProblems": "onProblem",
|
||||
"focus": false,
|
||||
"panel": "shared",
|
||||
"panel": "dedicated",
|
||||
"showReuseMessage": false,
|
||||
"clear": false,
|
||||
}
|
||||
"close": true
|
||||
},
|
||||
"problemMatcher": []
|
||||
},
|
||||
{
|
||||
"label": "jmavsim",
|
||||
|
@ -81,24 +83,28 @@
|
|||
"presentation": {
|
||||
"echo": true,
|
||||
"reveal": "never",
|
||||
"revealProblems": "onProblem",
|
||||
"focus": false,
|
||||
"panel": "shared",
|
||||
"panel": "dedicated",
|
||||
"showReuseMessage": false,
|
||||
"clear": false
|
||||
"clear": false,
|
||||
"close": true
|
||||
},
|
||||
"problemMatcher": []
|
||||
},
|
||||
{
|
||||
"label": "jmavsim kill",
|
||||
"type": "shell",
|
||||
"command": "kill $(ps aux | grep jmavsim | grep -v 'grep' | awk '{print $2}')",
|
||||
"command": "kill $(ps aux | grep jmavsim | grep -v 'grep' | awk '{print $2}') || true",
|
||||
"presentation": {
|
||||
"echo": false,
|
||||
"echo": true,
|
||||
"reveal": "never",
|
||||
"revealProblems": "onProblem",
|
||||
"focus": false,
|
||||
"panel": "shared",
|
||||
"panel": "dedicated",
|
||||
"showReuseMessage": false,
|
||||
"clear": false
|
||||
"clear": false,
|
||||
"close": true
|
||||
},
|
||||
"problemMatcher": [],
|
||||
"dependsOn":["px4_sitl_cleanup"]
|
||||
|
@ -110,15 +116,17 @@
|
|||
"options": {
|
||||
"cwd": "${workspaceFolder}"
|
||||
},
|
||||
"problemMatcher": [],
|
||||
"presentation":{
|
||||
"presentation": {
|
||||
"echo": true,
|
||||
"reveal": "always",
|
||||
"reveal": "never",
|
||||
"revealProblems": "onProblem",
|
||||
"focus": false,
|
||||
"panel": "shared",
|
||||
"panel": "dedicated",
|
||||
"showReuseMessage": false,
|
||||
"clear": false,
|
||||
}
|
||||
"close": true
|
||||
},
|
||||
"problemMatcher": [],
|
||||
},
|
||||
{
|
||||
"label": "gazebo start",
|
||||
|
@ -132,15 +140,17 @@
|
|||
"PX4_SIM_SPEED_FACTOR": "1"
|
||||
}
|
||||
},
|
||||
"command": "gzserver --verbose ${workspaceFolder}/Tools/simulation/gazebo/sitl_gazebo/worlds/${input:gazeboWorld}.world",
|
||||
"command": "gzserver --verbose ${workspaceFolder}/Tools/simulation/gazebo/sitl_gazebo/worlds/empty.world",
|
||||
"isBackground": true,
|
||||
"presentation": {
|
||||
"echo": true,
|
||||
"reveal": "never",
|
||||
"revealProblems": "onProblem",
|
||||
"focus": false,
|
||||
"panel": "shared",
|
||||
"panel": "dedicated",
|
||||
"showReuseMessage": false,
|
||||
"clear": false
|
||||
"clear": false,
|
||||
"close": true
|
||||
},
|
||||
"problemMatcher": [
|
||||
{
|
||||
|
@ -172,15 +182,17 @@
|
|||
"PX4_SIM_SPEED_FACTOR": "1"
|
||||
}
|
||||
},
|
||||
"command": "gz model --verbose --spawn-file=${workspaceFolder}/Tools/simulation/gazebo/sitl_gazebo/models/${input:gazeboModel}/${input:gazeboModel}.sdf --model-name=${input:gazeboModel} -x 1.01 -y 0.98 -z 0.83",
|
||||
"command": "gz model --verbose --spawn-file=${workspaceFolder}/Tools/simulation/gazebo/sitl_gazebo/models/iris/iris.sdf --model-name=iris -x 1.01 -y 0.98 -z 0.83",
|
||||
"isBackground": false,
|
||||
"presentation": {
|
||||
"echo": true,
|
||||
"reveal": "never",
|
||||
"revealProblems": "onProblem",
|
||||
"focus": false,
|
||||
"panel": "shared",
|
||||
"panel": "dedicated",
|
||||
"showReuseMessage": false,
|
||||
"clear": false
|
||||
"clear": false,
|
||||
"close": true
|
||||
},
|
||||
"problemMatcher": [
|
||||
{
|
||||
|
@ -207,38 +219,22 @@
|
|||
"cwd": "${workspaceFolder}",
|
||||
"env": {
|
||||
"IGN_GAZEBO_RESOURCE_PATH": "${workspaceFolder}/Tools/simulation/ignition/models",
|
||||
"PX4_SIM_SPEED_FACTOR": "1"
|
||||
}
|
||||
},
|
||||
"command": "ign gazebo -v 4 -r ${workspaceFolder}/Tools/simulation/ignition/worlds/${input:ignWorld}.sdf",
|
||||
"isBackground": true,
|
||||
"presentation": {
|
||||
"echo": true,
|
||||
"reveal": "never",
|
||||
"reveal": "always",
|
||||
"revealProblems": "onProblem",
|
||||
"focus": false,
|
||||
"focus": true,
|
||||
"panel": "dedicated",
|
||||
"showReuseMessage": false,
|
||||
"clear": false,
|
||||
"close": true
|
||||
"close": false
|
||||
},
|
||||
"problemMatcher": [
|
||||
{
|
||||
"pattern": [
|
||||
{
|
||||
"regexp": ".",
|
||||
"file": 1,
|
||||
"location": 2,
|
||||
"message": 3
|
||||
}
|
||||
],
|
||||
"background": {
|
||||
"activeOnStart": true,
|
||||
"beginsPattern": ".",
|
||||
"endsPattern": ".",
|
||||
}
|
||||
}
|
||||
]
|
||||
"problemMatcher": [],
|
||||
"dependsOn":["ign gazebo kill"]
|
||||
},
|
||||
{
|
||||
"label": "gazebo kill",
|
||||
|
@ -260,7 +256,7 @@
|
|||
{
|
||||
"label": "ign gazebo kill",
|
||||
"type": "shell",
|
||||
"command": "pkill -9 -f ign || true",
|
||||
"command": "pkill -9 -f 'ign gazebo' || true",
|
||||
"presentation": {
|
||||
"echo": true,
|
||||
"reveal": "never",
|
||||
|
@ -352,40 +348,6 @@
|
|||
"default"
|
||||
],
|
||||
"default": "default"
|
||||
},
|
||||
{
|
||||
"type": "pickString",
|
||||
"id": "gazeboModel",
|
||||
"description": "gazebo model",
|
||||
"options": [
|
||||
"iris",
|
||||
"typhoon_h480",
|
||||
"plane",
|
||||
"plane_catapult",
|
||||
"plane_lidar",
|
||||
"standard_vtol",
|
||||
"tailsitter",
|
||||
"tiltrotor",
|
||||
"r1_rover",
|
||||
"boat"
|
||||
],
|
||||
"default": "iris"
|
||||
},
|
||||
{
|
||||
"type": "pickString",
|
||||
"id": "gazeboWorld",
|
||||
"description": "gazebo world",
|
||||
"options": [
|
||||
"baylands",
|
||||
"empty",
|
||||
"ksql_airport",
|
||||
"mcmillan_airfield",
|
||||
"sonoma_raceway",
|
||||
"warehouse",
|
||||
"windy",
|
||||
"yosemite"
|
||||
],
|
||||
"default": "empty"
|
||||
}
|
||||
]
|
||||
}
|
||||
|
|
|
@ -33,11 +33,11 @@ elif [ "$PX4_SIMULATOR" = "ignition" ]; then
|
|||
# starting ign gazebo with ${PX4_SIM_WORLD} world
|
||||
echo "INFO [init] starting ign gazebo"
|
||||
|
||||
ign gazebo --verbose=1 -r -s "${PX4_IGN_GAZEBO_WORLDS}/${PX4_SIM_WORLD}.sdf" &
|
||||
|
||||
if [ -z $HEADLESS ]; then
|
||||
ign gazebo --verbose=1 -r "${PX4_IGN_GAZEBO_WORLDS}/${PX4_SIM_WORLD}.sdf" &
|
||||
else
|
||||
# starting ign gazebo headless
|
||||
ign gazebo --verbose=1 -r -s "${PX4_IGN_GAZEBO_WORLDS}/${PX4_SIM_WORLD}.sdf" &
|
||||
# HEADLESS not set, starting ign gazebo gui
|
||||
ign gazebo -g &
|
||||
fi
|
||||
else
|
||||
echo "INFO [init] ign gazebo already running world: $ign_world"
|
||||
|
|
|
@ -1,6 +1,9 @@
|
|||
#!/bin/sh
|
||||
|
||||
set -e
|
||||
# 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
|
||||
|
||||
# PX4 commands need the 'px4-' prefix in bash.
|
||||
# (px4-alias.sh is expected to be in the PATH)
|
||||
|
@ -66,7 +69,7 @@ set PARAM_BACKUP_FILE parameters_backup.bson
|
|||
|
||||
param select $PARAM_FILE
|
||||
if [ -f $PARAM_FILE ]; then
|
||||
set +e # disable exit on error control for param import
|
||||
|
||||
if ! param import
|
||||
then
|
||||
echo "ERROR [init] param import failed"
|
||||
|
@ -92,7 +95,6 @@ if [ -f $PARAM_FILE ]; then
|
|||
|
||||
param status
|
||||
fi
|
||||
set -e # restore exit on error control
|
||||
|
||||
elif [ -f $PARAM_BACKUP_FILE ]; then
|
||||
echo "ERROR [init] primary param file $PARAM_FILE unavailable, using backup $PARAM_BACKUP_FILE"
|
||||
|
|
|
@ -40,6 +40,7 @@ CONFIG_MODULES_REPLAY=y
|
|||
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_COMMON_SIMULATION=y
|
||||
CONFIG_MODULES_SIMULATION_SIMULATOR_IGNITION_BRIDGE=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
|
|
|
@ -1,7 +0,0 @@
|
|||
CONFIG_COMMON_SIMULATION=n
|
||||
CONFIG_BOARD_LOCKSTEP=y
|
||||
CONFIG_MODULES_SIMULATION_BATTERY_SIMULATOR=y
|
||||
CONFIG_MODULES_SIMULATION_SENSOR_BARO_SIM=y
|
||||
CONFIG_MODULES_SIMULATION_SENSOR_GPS_SIM=y
|
||||
CONFIG_MODULES_SIMULATION_SENSOR_MAG_SIM=y
|
||||
CONFIG_MODULES_SIMULATION_SIMULATOR_IGNITION_BRIDGE=y
|
|
@ -113,11 +113,8 @@ elseif("${PX4_BOARD}" MATCHES "sitl")
|
|||
if(${PX4_BOARD_LABEL} MATCHES "replay")
|
||||
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/Debug/launch_replay.json.in ${PX4_SOURCE_DIR}/.vscode/launch.json COPYONLY)
|
||||
|
||||
elseif(${PX4_CONFIG} MATCHES "px4_sitl_ign")
|
||||
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/Debug/launch_sitl_ignition.json.in ${PX4_SOURCE_DIR}/.vscode/launch.json COPYONLY)
|
||||
|
||||
else()
|
||||
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/Debug/launch_sitl_default.json.in ${PX4_SOURCE_DIR}/.vscode/launch.json COPYONLY)
|
||||
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/Debug/launch_sitl.json.in ${PX4_SOURCE_DIR}/.vscode/launch.json COPYONLY)
|
||||
endif()
|
||||
|
||||
set(SITL_WORKING_DIR ${PX4_BINARY_DIR}/rootfs)
|
||||
|
|
|
@ -1,6 +1,51 @@
|
|||
{
|
||||
"version": "0.2.0",
|
||||
"configurations": [
|
||||
{
|
||||
"name": "SITL (Ignition Gazebo)",
|
||||
"type": "cppdbg",
|
||||
"request": "launch",
|
||||
"program": "${command:cmake.launchTargetPath}",
|
||||
"args": [
|
||||
"${workspaceFolder}/ROMFS/px4fmu_common",
|
||||
"-s", "etc/init.d-posix/rcS"
|
||||
],
|
||||
"stopAtEntry": false,
|
||||
"cwd": "${command:cmake.buildDirectory}/rootfs",
|
||||
"environment": [
|
||||
{
|
||||
"name": "PX4_SIM_MODEL",
|
||||
"value": "${input:PX4_IGN_GZ_SIM_MODEL}"
|
||||
}
|
||||
],
|
||||
"externalConsole": false,
|
||||
"postDebugTask": "ign gazebo kill",
|
||||
"linux": {
|
||||
"MIMode": "gdb",
|
||||
"externalConsole": false,
|
||||
"setupCommands": [
|
||||
{
|
||||
"description": "Enable pretty-printing for gdb",
|
||||
"text": "-enable-pretty-printing",
|
||||
"ignoreFailures": true
|
||||
},
|
||||
{
|
||||
"description": "PX4 ignore wq signals",
|
||||
"text": "handle SIGCONT nostop noprint nopass",
|
||||
"ignoreFailures": true
|
||||
}
|
||||
]
|
||||
},
|
||||
"osx": {
|
||||
"MIMode": "lldb",
|
||||
"externalConsole": true,
|
||||
"setupCommands": [
|
||||
{
|
||||
"text": "pro hand -p true -s false -n false SIGCONT",
|
||||
}
|
||||
]
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "SITL (sihsim 10040_quadx)",
|
||||
"type": "cppdbg",
|
||||
|
@ -46,7 +91,7 @@
|
|||
}
|
||||
},
|
||||
{
|
||||
"name": "SITL (Gazebo Classic)",
|
||||
"name": "SITL (Gazebo Classic iris)",
|
||||
"type": "cppdbg",
|
||||
"request": "launch",
|
||||
"program": "${command:cmake.launchTargetPath}",
|
||||
|
@ -58,7 +103,7 @@
|
|||
"environment": [
|
||||
{
|
||||
"name": "PX4_SIM_MODEL",
|
||||
"value": "${input:PX4_SIM_MODEL}"
|
||||
"value": "iris"
|
||||
}
|
||||
],
|
||||
"externalConsole": false,
|
||||
|
@ -106,6 +151,7 @@
|
|||
"value": "iris"
|
||||
}
|
||||
],
|
||||
"externalConsole": false,
|
||||
"preLaunchTask": "jmavsim",
|
||||
"postDebugTask": "jmavsim kill",
|
||||
"linux": {
|
||||
|
@ -180,21 +226,12 @@
|
|||
"inputs": [
|
||||
{
|
||||
"type": "pickString",
|
||||
"id": "PX4_SIM_MODEL",
|
||||
"description": "PX4_SIM_MODEL",
|
||||
"id": "PX4_IGN_GZ_SIM_MODEL",
|
||||
"description": "Ignition Gazebo vehicle model",
|
||||
"options": [
|
||||
"iris",
|
||||
"typhoon_h480",
|
||||
"plane",
|
||||
"plane_catapult",
|
||||
"plane_lidar",
|
||||
"standard_vtol",
|
||||
"tailsitter",
|
||||
"tiltrotor",
|
||||
"r1_rover",
|
||||
"boat"
|
||||
"x500",
|
||||
],
|
||||
"default": "iris"
|
||||
}
|
||||
"default": "x500"
|
||||
}
|
||||
]
|
||||
}
|
|
@ -1,63 +0,0 @@
|
|||
{
|
||||
"version": "0.2.0",
|
||||
"configurations": [
|
||||
{
|
||||
"name": "SITL (Ignition Gazebo)",
|
||||
"type": "cppdbg",
|
||||
"request": "launch",
|
||||
"program": "${command:cmake.launchTargetPath}",
|
||||
"args": [
|
||||
"${workspaceFolder}/ROMFS/px4fmu_common",
|
||||
"-s", "etc/init.d-posix/rcS"
|
||||
],
|
||||
"stopAtEntry": false,
|
||||
"cwd": "${command:cmake.buildDirectory}/rootfs",
|
||||
"environment": [
|
||||
{
|
||||
"name": "PX4_SIM_MODEL",
|
||||
"value": "${input:PX4_SIM_MODEL}"
|
||||
}
|
||||
],
|
||||
"externalConsole": false,
|
||||
"preLaunchTask": "ign gazebo",
|
||||
"postDebugTask": "ign gazebo kill",
|
||||
"linux": {
|
||||
"MIMode": "gdb",
|
||||
"externalConsole": false,
|
||||
"setupCommands": [
|
||||
{
|
||||
"description": "Enable pretty-printing for gdb",
|
||||
"text": "-enable-pretty-printing",
|
||||
"ignoreFailures": true
|
||||
},
|
||||
{
|
||||
"description": "PX4 ignore wq signals",
|
||||
"text": "handle SIGCONT nostop noprint nopass",
|
||||
"ignoreFailures": true
|
||||
}
|
||||
]
|
||||
},
|
||||
"osx": {
|
||||
"MIMode": "lldb",
|
||||
"externalConsole": true,
|
||||
"setupCommands": [
|
||||
{
|
||||
"text": "pro hand -p true -s false -n false SIGCONT",
|
||||
}
|
||||
]
|
||||
}
|
||||
}
|
||||
],
|
||||
"inputs": [
|
||||
{
|
||||
"type": "pickString",
|
||||
"id": "PX4_SIM_MODEL",
|
||||
"description": "PX4_SIM_MODEL",
|
||||
"options": [
|
||||
"x500",
|
||||
"x4"
|
||||
],
|
||||
"default": "x500"
|
||||
}
|
||||
]
|
||||
}
|
|
@ -31,71 +31,76 @@
|
|||
#
|
||||
############################################################################
|
||||
|
||||
add_compile_options(-frtti -fexceptions)
|
||||
|
||||
# Find the Ignition_Transport library
|
||||
find_package(ignition-transport
|
||||
REQUIRED COMPONENTS core
|
||||
#REQUIRED COMPONENTS core
|
||||
NAMES
|
||||
ignition-transport8
|
||||
ignition-transport10
|
||||
ignition-transport11
|
||||
#QUIET
|
||||
)
|
||||
set(IGN_TRANSPORT_VER ${ignition-transport_VERSION_MAJOR})
|
||||
|
||||
px4_add_module(
|
||||
MODULE modules__simulation__ignition_bridge
|
||||
MAIN simulator_ignition_bridge
|
||||
COMPILE_FLAGS
|
||||
${MAX_CUSTOM_OPT_LEVEL}
|
||||
SRCS
|
||||
SimulatorIgnitionBridge.cpp
|
||||
SimulatorIgnitionBridge.hpp
|
||||
DEPENDS
|
||||
mixer_module
|
||||
px4_work_queue
|
||||
ignition-transport${IGN_TRANSPORT_VER}::core
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
)
|
||||
if(ignition-transport_FOUND)
|
||||
|
||||
file(GLOB ign_models
|
||||
LIST_DIRECTORIES true
|
||||
RELATIVE ${PX4_SOURCE_DIR}/Tools/simulation/ignition/models
|
||||
CONFIGURE_DEPENDS
|
||||
${PX4_SOURCE_DIR}/Tools/simulation/ignition/models/*
|
||||
)
|
||||
add_compile_options(-frtti -fexceptions)
|
||||
|
||||
file(GLOB ign_worlds
|
||||
CONFIGURE_DEPENDS
|
||||
${PX4_SOURCE_DIR}/Tools/simulation/ignition/worlds/*.sdf
|
||||
)
|
||||
set(IGN_TRANSPORT_VER ${ignition-transport_VERSION_MAJOR})
|
||||
|
||||
foreach(model ${ign_models})
|
||||
foreach(world ${ign_worlds})
|
||||
px4_add_module(
|
||||
MODULE modules__simulation__ignition_bridge
|
||||
MAIN simulator_ignition_bridge
|
||||
COMPILE_FLAGS
|
||||
${MAX_CUSTOM_OPT_LEVEL}
|
||||
SRCS
|
||||
SimulatorIgnitionBridge.cpp
|
||||
SimulatorIgnitionBridge.hpp
|
||||
DEPENDS
|
||||
mixer_module
|
||||
px4_work_queue
|
||||
ignition-transport${IGN_TRANSPORT_VER}::core
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
)
|
||||
|
||||
get_filename_component("world_name" ${world} NAME_WE)
|
||||
file(GLOB ign_models
|
||||
LIST_DIRECTORIES true
|
||||
RELATIVE ${PX4_SOURCE_DIR}/Tools/simulation/ignition/models
|
||||
CONFIGURE_DEPENDS
|
||||
${PX4_SOURCE_DIR}/Tools/simulation/ignition/models/*
|
||||
)
|
||||
|
||||
if(world_name MATCHES "default")
|
||||
add_custom_target(ign_${model}
|
||||
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=${model} $<TARGET_FILE:px4>
|
||||
WORKING_DIRECTORY ${SITL_WORKING_DIR}
|
||||
USES_TERMINAL
|
||||
DEPENDS px4
|
||||
)
|
||||
else()
|
||||
add_custom_target(ign_${model}_${world_name}
|
||||
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=${model} PX4_SIM_WORLD=${world_name} $<TARGET_FILE:px4>
|
||||
WORKING_DIRECTORY ${SITL_WORKING_DIR}
|
||||
USES_TERMINAL
|
||||
DEPENDS px4
|
||||
)
|
||||
endif()
|
||||
file(GLOB ign_worlds
|
||||
CONFIGURE_DEPENDS
|
||||
${PX4_SOURCE_DIR}/Tools/simulation/ignition/worlds/*.sdf
|
||||
)
|
||||
|
||||
foreach(model ${ign_models})
|
||||
foreach(world ${ign_worlds})
|
||||
|
||||
get_filename_component("world_name" ${world} NAME_WE)
|
||||
|
||||
if(world_name MATCHES "default")
|
||||
add_custom_target(ign_${model}
|
||||
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=${model} $<TARGET_FILE:px4>
|
||||
WORKING_DIRECTORY ${SITL_WORKING_DIR}
|
||||
USES_TERMINAL
|
||||
DEPENDS px4
|
||||
)
|
||||
else()
|
||||
add_custom_target(ign_${model}_${world_name}
|
||||
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=${model} PX4_SIM_WORLD=${world_name} $<TARGET_FILE:px4>
|
||||
WORKING_DIRECTORY ${SITL_WORKING_DIR}
|
||||
USES_TERMINAL
|
||||
DEPENDS px4
|
||||
)
|
||||
endif()
|
||||
endforeach()
|
||||
endforeach()
|
||||
endforeach()
|
||||
|
||||
|
||||
# TODO: PX4_IGN_MODELS_PATH
|
||||
# PX4_IGN_WORLDS_PATH
|
||||
configure_file(gazebo_env.sh.in ${PX4_BINARY_DIR}/rootfs/gazebo_env.sh)
|
||||
# TODO: PX4_IGN_MODELS_PATH
|
||||
# PX4_IGN_WORLDS_PATH
|
||||
configure_file(gazebo_env.sh.in ${PX4_BINARY_DIR}/rootfs/gazebo_env.sh)
|
||||
|
||||
endif()
|
||||
|
|
|
@ -237,6 +237,7 @@ int SimulatorIgnitionBridge::task_spawn(int argc, char *argv[])
|
|||
|
||||
bool SimulatorIgnitionBridge::updateClock(const uint64_t tv_sec, const uint64_t tv_nsec)
|
||||
{
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
struct timespec ts;
|
||||
ts.tv_sec = tv_sec;
|
||||
ts.tv_nsec = tv_nsec;
|
||||
|
@ -246,6 +247,8 @@ bool SimulatorIgnitionBridge::updateClock(const uint64_t tv_sec, const uint64_t
|
|||
return true;
|
||||
}
|
||||
|
||||
#endif // ENABLE_LOCKSTEP_SCHEDULER
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue