Skip to content

Commit

Permalink
feat: spacecraft build
Browse files Browse the repository at this point in the history
  • Loading branch information
Pedro-Roque committed Jan 20, 2025
1 parent 33620b3 commit d4b6d75
Show file tree
Hide file tree
Showing 7 changed files with 1,558 additions and 1 deletion.
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ if(CONFIG_MODULES_ROVER_ACKERMANN)
)
endif()

if(true)
if(CONFIG_MODULES_SC_CONTROL_ALLOCATOR)
px4_add_romfs_files(
rc.sc_apps
rc.sc_defaults
Expand Down
17 changes: 17 additions & 0 deletions boards/px4/sitl/spacecraft.px4board
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
CONFIG_MODULES_AIRSPEED_SELECTOR=n
CONFIG_MODULES_FLIGHT_MODE_MANAGER=n
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_FW_POS_CONTROL=n
CONFIG_MODULES_FW_RATE_CONTROL=n
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_MC_ATT_CONTROL=n
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
CONFIG_MODULES_MC_POS_CONTROL=n
CONFIG_MODULES_MC_RATE_CONTROL=n
CONFIG_MODULES_VTOL_ATT_CONTROL=n
CONFIG_MODULES_DIFFERENTIAL_DRIVE=n
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
CONFIG_MODULES_CONTROL_ALLOCATOR=n
CONFIG_MODULES_SC_CONTROL_ALLOCATOR=y
51 changes: 51 additions & 0 deletions src/modules/sc_control_allocator/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
############################################################################
#
# Copyright (c) 2019 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_directories(${CMAKE_CURRENT_SOURCE_DIR})

px4_add_module(
MODULE modules__sc_control_allocator
MAIN sc_control_allocator
COMPILE_FLAGS
${MAX_CUSTOM_OPT_LEVEL}
STACK_MAIN
3000
SRCS
ControlAllocator.cpp
ControlAllocator.hpp
MODULE_CONFIG
module.yaml
DEPENDS
mathlib
px4_work_queue
)
91 changes: 91 additions & 0 deletions src/modules/sc_control_allocator/ControlAllocator.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
/****************************************************************************
*
* Copyright (c) 2013-2019 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 ControlAllocator.cpp
*
* Control allocator.
*
* @author Julien Lecoeur <[email protected]>
*/

#include "ControlAllocator.hpp"

int ControlAllocator::task_spawn(int argc, char *argv[])
{
return 0;
}

int ControlAllocator::print_status()
{
PX4_INFO("Running");

return 0;
}

int ControlAllocator::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}

int ControlAllocator::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}

PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
This implements control allocation for spacecraft vehicles.
It takes torque and thrust setpoints as inputs and outputs
actuator setpoint messages.
)DESCR_STR"
);

PRINT_MODULE_USAGE_NAME("sc_control_allocator", "controller");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();

return 0;
}

/**
* Control Allocator app start / stop handling function
*/
extern "C" __EXPORT int sc_control_allocator_main(int argc, char *argv[]);

int sc_control_allocator_main(int argc, char *argv[])
{
return ControlAllocator::main(argc, argv);
}
87 changes: 87 additions & 0 deletions src/modules/sc_control_allocator/ControlAllocator.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
/****************************************************************************
*
* Copyright (c) 2013-2019 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 ControlAllocator.hpp
*
* Control allocator.
*
* @author Julien Lecoeur <[email protected]>
*/

#pragma once

#include <lib/matrix/matrix/math.hpp>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/actuator_motors.h>
#include <uORB/topics/actuator_servos.h>
#include <uORB/topics/actuator_servos_trim.h>
#include <uORB/topics/control_allocator_status.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_torque_setpoint.h>
#include <uORB/topics/vehicle_thrust_setpoint.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/failure_detector_status.h>

class ControlAllocator : public ModuleBase<ControlAllocator>, public ModuleParams, public px4::ScheduledWorkItem
{
public:

ControlAllocator();

virtual ~ControlAllocator();

/** @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);

/** @see ModuleBase::print_status() */
int print_status() override;

private: /**< loop duration performance counter */

};
12 changes: 12 additions & 0 deletions src/modules/sc_control_allocator/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
menuconfig MODULES_SC_CONTROL_ALLOCATOR
bool "sc_control_allocator"
default n
---help---
Enable support for control_allocator

menuconfig USER_SC_CONTROL_ALLOCATOR
bool "control_allocator running as userspace module"
default y
depends on BOARD_PROTECTED && MODULES_SC_CONTROL_ALLOCATOR
---help---
Put sc_control_allocator in userspace memory
Loading

0 comments on commit d4b6d75

Please sign in to comment.