Rover module: Temp

This commit is contained in:
PerFrivik 2023-12-19 15:04:34 +01:00
parent 7cbc6241d7
commit a471755dac
60 changed files with 347 additions and 66 deletions

View File

@ -80,6 +80,7 @@ px4_add_romfs_files(
4005_gz_x500_vision
4006_gz_px4vision
4008_gz_advanced_plane
4009_gz_r1_rover
4010_gz_x500_mono_cam
6011_gazebo-classic_typhoon_h480

View File

@ -5,7 +5,7 @@
ekf2 start &
# Start rover differential drive controller.
differential_drive_control start
rover_control start
# Start Land Detector.
land_detector start rover

View File

@ -0,0 +1,20 @@
{
"configurations": [
{
"browse": {
"databaseFilename": "${default}",
"limitSymbolsToIncludedHeaders": false
},
"includePath": [
"/opt/ros/humble/include/**",
"/usr/include/**"
],
"name": "ROS",
"intelliSenseMode": "gcc-x64",
"compilerPath": "/usr/bin/gcc",
"cStandard": "gnu11",
"cppStandard": "c++14"
}
],
"version": 4
}

10
Tools/simulation/.vscode/settings.json vendored Normal file
View File

@ -0,0 +1,10 @@
{
"python.autoComplete.extraPaths": [
"/opt/ros/humble/lib/python3.10/site-packages",
"/opt/ros/humble/local/lib/python3.10/dist-packages"
],
"python.analysis.extraPaths": [
"/opt/ros/humble/lib/python3.10/site-packages",
"/opt/ros/humble/local/lib/python3.10/dist-packages"
]
}

View File

@ -39,7 +39,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -39,7 +39,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -36,7 +36,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -25,7 +25,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -43,7 +43,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -44,7 +44,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -39,7 +39,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -27,7 +27,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -37,7 +37,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -32,7 +32,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
# CONFIG_EKF2_AUXVEL is not set
# CONFIG_EKF2_BARO_COMPENSATION is not set

View File

@ -31,7 +31,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
# CONFIG_EKF2_AUXVEL is not set
# CONFIG_EKF2_BARO_COMPENSATION is not set

View File

@ -32,7 +32,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
# CONFIG_EKF2_AUXVEL is not set
# CONFIG_EKF2_BARO_COMPENSATION is not set

View File

@ -43,7 +43,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -41,7 +41,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -36,7 +36,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -37,7 +37,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -37,7 +37,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -35,7 +35,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -36,7 +36,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -35,7 +35,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -38,7 +38,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -39,7 +39,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -40,7 +40,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -41,7 +41,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -28,7 +28,7 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y

View File

@ -15,7 +15,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y

View File

@ -20,7 +20,7 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FW_ATT_CONTROL=y

View File

@ -1,4 +1,4 @@
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=n
CONFIG_MODULES_MC_ATT_CONTROL=n
CONFIG_MODULES_MC_POS_CONTROL=n

View File

@ -43,7 +43,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -44,7 +44,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -40,7 +40,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -48,7 +48,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -53,7 +53,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -37,7 +37,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -40,7 +40,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -37,7 +37,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y

View File

@ -24,7 +24,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -12,7 +12,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
CONFIG_MODULES_EVENTS=y

View File

@ -27,7 +27,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y

View File

@ -31,7 +31,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -37,7 +37,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -37,7 +37,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_ROVER_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y

View File

@ -239,7 +239,7 @@ ControlAllocator::update_effectiveness_source()
break;
case EffectivenessSource::ROVER_DIFFERENTIAL:
// differential_drive_control does allocation and publishes directly to actuator_motors topic
// rover_control does allocation and publishes directly to actuator_motors topic
break;
case EffectivenessSource::FIXED_WING:

View File

@ -34,11 +34,13 @@
add_subdirectory(DifferentialDriveKinematics)
px4_add_module(
MODULE modules__differential_drive_control
MAIN differential_drive_control
MODULE modules__rover_control
MAIN rover_control
SRCS
DifferentialDriveControl.cpp
DifferentialDriveControl.hpp
RoverControl.cpp
RoverControl.hpp
DEPENDS
DifferentialDriveKinematics
px4_work_queue

View File

@ -38,8 +38,8 @@ using namespace matrix;
namespace differential_drive_control
{
DifferentialDriveControl::DifferentialDriveControl() :
ModuleParams(nullptr),
DifferentialDriveControl::DifferentialDriveControl(ModuleParams *parent) :
ModuleParams(parent),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl)
{
updateParams();
@ -47,7 +47,7 @@ DifferentialDriveControl::DifferentialDriveControl() :
bool DifferentialDriveControl::init()
{
ScheduleOnInterval(10_ms); // 100 Hz
// ScheduleOnInterval(10_ms); // 100 Hz
return true;
}
@ -128,27 +128,33 @@ void DifferentialDriveControl::Run()
_actuator_motors_pub.publish(actuator_motors);
}
void DifferentialDriveControl::Update()
{
Run();
}
int DifferentialDriveControl::task_spawn(int argc, char *argv[])
{
DifferentialDriveControl *instance = new DifferentialDriveControl();
// DifferentialDriveControl *instance = new DifferentialDriveControl();
if (instance) {
_object.store(instance);
_task_id = task_id_is_work_queue;
// if (instance) {
// _object.store(instance);
// _task_id = task_id_is_work_queue;
if (instance->init()) {
return PX4_OK;
}
// if (instance->init()) {
// return PX4_OK;
// }
} else {
PX4_ERR("alloc failed");
}
// } else {
// PX4_ERR("alloc failed");
// }
delete instance;
_object.store(nullptr);
_task_id = -1;
// delete instance;
// _object.store(nullptr);
// _task_id = -1;
return PX4_ERROR;
// return PX4_ERROR;
return PX4_OK;
}
int DifferentialDriveControl::custom_command(int argc, char *argv[])

View File

@ -66,7 +66,7 @@ class DifferentialDriveControl : public ModuleBase<DifferentialDriveControl>, pu
public px4::ScheduledWorkItem
{
public:
DifferentialDriveControl();
DifferentialDriveControl(ModuleParams *parent);
~DifferentialDriveControl() override = default;
/** @see ModuleBase */
@ -80,6 +80,8 @@ public:
bool init();
void Update();
protected:
void updateParams() override;

View File

@ -1,5 +1,5 @@
menuconfig MODULES_DIFFERENTIAL_DRIVE_CONTROL
bool "differential_drive_control"
menuconfig MODULES_ROVER_CONTROL
bool "ROVER_CONTROL"
default n
depends on MODULES_CONTROL_ALLOCATOR
---help---

View File

@ -0,0 +1,122 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#include "RoverControl.hpp"
using namespace time_literals;
using namespace matrix;
namespace rover_control
{
RoverControl::RoverControl() :
ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl),
_differential_drive_control(this)
{
updateParams();
}
bool RoverControl::init()
{
ScheduleOnInterval(10_ms); // 100 Hz
return true;
}
void RoverControl::updateParams()
{
ModuleParams::updateParams();
}
void RoverControl::Run()
{
if (should_exit()) {
ScheduleClear();
exit_and_cleanup();
}
_differential_drive_control.Update();
}
int RoverControl::task_spawn(int argc, char *argv[])
{
RoverControl *instance = new RoverControl();
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 RoverControl::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
int RoverControl::print_usage(const char *reason)
{
if (reason) {
PX4_ERR("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
Rover state machine.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("rover_control", "controller");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}
extern "C" __EXPORT int rover_control_main(int argc, char *argv[])
{
return RoverControl::main(argc, argv);
}
} // namespace rover_control

View File

@ -0,0 +1,118 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#pragma once
// PX4 includes
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
// uORB includes
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_motors.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionMultiArray.hpp>
#include <uORB/topics/differential_drive_setpoint.h>
// Standard library includes
#include <math.h>
// Local includes
#include <DifferentialDriveKinematics.hpp>
#include "DifferentialDriveControl.hpp"
namespace rover_control
{
class RoverControl : public ModuleBase<RoverControl>, public ModuleParams,
public px4::ScheduledWorkItem
{
public:
RoverControl();
~RoverControl() override = default;
/** @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();
protected:
void updateParams() override;
private:
void Run() override;
uORB::Subscription _differential_drive_setpoint_sub{ORB_ID(differential_drive_setpoint)};
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
uORB::PublicationMulti<actuator_motors_s> _actuator_motors_pub{ORB_ID(actuator_motors)};
uORB::Publication<differential_drive_setpoint_s> _differential_drive_setpoint_pub{ORB_ID(differential_drive_setpoint)};
// differential_drive_setpoint_s _differential_drive_setpoint{};
// DifferentialDriveKinematics _differential_drive_kinematics{};
differential_drive_control::DifferentialDriveControl _differential_drive_control;
bool _armed = false;
bool _manual_driving = false;
float _max_speed{0.f};
float _max_angular_velocity{0.f};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::RDD_SPEED_SCALE>) _param_rdd_speed_scale,
(ParamFloat<px4::params::RDD_ANG_SCALE>) _param_rdd_ang_velocity_scale,
(ParamFloat<px4::params::RDD_WHL_SPEED>) _param_rdd_max_wheel_speed,
(ParamFloat<px4::params::RDD_WHEEL_BASE>) _param_rdd_wheel_base,
(ParamFloat<px4::params::RDD_WHEEL_RADIUS>) _param_rdd_wheel_radius,
(ParamInt<px4::params::CA_R_REV>) _param_r_rev
)
};
} // namespace rover_control