forked from Archive/PX4-Autopilot
Linux: Added linker script support for param and added mc_att_control
Added linker script to resolve __param_start and __param_end. Added mc_att_control to list of supported builtins. Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
parent
977036faf9
commit
2cd44a24ea
3
Makefile
3
Makefile
|
@ -143,6 +143,9 @@ testbuild:
|
|||
$(Q) (cd $(PX4_BASE) && $(MAKE) distclean && $(MAKE) archives && $(MAKE) -j8)
|
||||
$(Q) (zip -r Firmware.zip $(PX4_BASE)/Images)
|
||||
|
||||
testrun:
|
||||
Tools/linux_run.sh
|
||||
|
||||
#
|
||||
# Unittest targets. Builds and runs the host-level
|
||||
# unit tests.
|
||||
|
|
|
@ -0,0 +1,17 @@
|
|||
#!/bin/bash
|
||||
|
||||
if [ ! -c /tmp/ttyS0 ] || [ ! -c /tmp/ttyS1 ]
|
||||
then
|
||||
echo "Need to create /tmp/ttyS[01]"
|
||||
echo "socat PTY,link=/tmp/ttyS0 PTY,link=/tmp/ttyS1"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
if [ ! -d /fs/msdcard ] && [ ! -w /fs/msdcard ]
|
||||
then
|
||||
echo "Need to create/mount writable /fs/microsd"
|
||||
echo "sudo mkdir -p /fs/msdcard"
|
||||
echo "sudo chmod 777 /fs/msdcard"
|
||||
fi
|
||||
|
||||
Build/linux_default.build/mainapp
|
|
@ -0,0 +1,61 @@
|
|||
/****************************************************************************
|
||||
* configs/aerocore/common/ld.script
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 NuttX 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F427 has 2048Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 256Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
||||
* 3) 64Kb of SRAM beginning at address 0x2002:0000
|
||||
* 4) 64Kb of TCM SRAM beginning at address 0x1000:0000
|
||||
*
|
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
|
||||
* where the code expects to begin execution by jumping to the entry point in
|
||||
* the 0x0800:0000 address range.
|
||||
*
|
||||
* The first 0x4000 of flash is reserved for the bootloader.
|
||||
*/
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
/*
|
||||
* Construction data for parameters.
|
||||
*/
|
||||
__param ALIGN(4): {
|
||||
__param_start = .;
|
||||
KEEP(*(__param*))
|
||||
__param_end = .;
|
||||
}
|
||||
}
|
|
@ -33,7 +33,7 @@ MODULES += modules/mavlink
|
|||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
#MODULES += modules/mc_att_control
|
||||
MODULES += modules/mc_att_control
|
||||
|
||||
#
|
||||
# Library modules
|
||||
|
|
|
@ -41,6 +41,7 @@
|
|||
# What we're going to build.
|
||||
#
|
||||
PRODUCT_SHARED_LIB = $(WORK_DIR)firmware.a
|
||||
PRODUCT_SHARED_PRELINK = $(WORK_DIR)firmware.o
|
||||
|
||||
.PHONY: firmware
|
||||
firmware: $(PRODUCT_SHARED_LIB) $(WORK_DIR)mainapp
|
||||
|
@ -49,8 +50,11 @@ firmware: $(PRODUCT_SHARED_LIB) $(WORK_DIR)mainapp
|
|||
# Built product rules
|
||||
#
|
||||
|
||||
$(PRODUCT_SHARED_LIB): $(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKFILES)
|
||||
$(call LINK_A,$@,$(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS))
|
||||
$(PRODUCT_SHARED_PRELINK): $(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKFILES)
|
||||
$(call PRELINKF,$@,$(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS))
|
||||
|
||||
$(PRODUCT_SHARED_LIB): $(PRODUCT_SHARED_PRELINK)
|
||||
$(call LINK_A,$@,$(PRODUCT_SHARED_PRELINK))
|
||||
|
||||
MAIN = $(PX4_BASE)/src/platforms/linux/main.cpp
|
||||
$(WORK_DIR)mainapp: $(PRODUCT_SHARED_LIB)
|
||||
|
|
|
@ -193,7 +193,7 @@ ARCHWARNINGSXX = $(ARCHWARNINGS) \
|
|||
# pull in *just* libm from the toolchain ... this is grody
|
||||
LIBM := $(shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a)
|
||||
#EXTRA_LIBS += $(LIBM)
|
||||
EXTRA_LIBS += -pthread -lm -lrt
|
||||
EXTRA_LIBS += -lm -lrt
|
||||
|
||||
# Flags we pass to the C compiler
|
||||
#
|
||||
|
@ -237,6 +237,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \
|
|||
$(EXTRADEFINES) \
|
||||
$(EXTRAAFLAGS)
|
||||
|
||||
LDSCRIPT = $(PX4_BASE)/linux-configs/linuxtest/scripts/ld.script
|
||||
# Flags we pass to the linker
|
||||
#
|
||||
LDFLAGS += $(EXTRALDFLAGS) \
|
||||
|
@ -290,6 +291,15 @@ define PRELINK
|
|||
@$(MKDIR) -p $(dir $1)
|
||||
$(Q) $(LD) -Ur -o $1 $2
|
||||
|
||||
endef
|
||||
# Produce partially-linked $1 from files in $2
|
||||
#
|
||||
#$(Q) $(LD) -Ur -o $1 $2 # -Ur not supported in ld.gold
|
||||
define PRELINKF
|
||||
@$(ECHO) "PRELINK: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
$(Q) $(LD) -Ur -T$(LDSCRIPT) -o $1 $2
|
||||
|
||||
endef
|
||||
# $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
|
||||
|
||||
|
@ -324,7 +334,7 @@ endef
|
|||
define LINK
|
||||
@$(ECHO) "LINK: $1"
|
||||
@$(MKDIR) -p $(dir $1)
|
||||
echo "$(Q) $(CXX) $(LDFLAGS) -o $1 $2 $(LIBS) $(EXTRA_LIBS)"
|
||||
$(Q) $(CXX) $(CXXFLAGS) $(LDFLAGS) -o $1 $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC)
|
||||
|
||||
endef
|
||||
|
||||
|
|
|
@ -54,6 +54,7 @@
|
|||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_tasks.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
@ -404,7 +405,7 @@ MulticopterAttitudeControl::~MulticopterAttitudeControl()
|
|||
|
||||
/* if we have given up, kill it */
|
||||
if (++i > 50) {
|
||||
task_delete(_control_task);
|
||||
px4_task_delete(_control_task);
|
||||
break;
|
||||
}
|
||||
} while (_control_task != -1);
|
||||
|
@ -721,7 +722,7 @@ MulticopterAttitudeControl::control_attitude_rates(float dt)
|
|||
if (fabsf(_att_control(i)) < _thrust_sp) {
|
||||
float rate_i = _rates_int(i) + _params.rate_i(i) * rates_err(i) * dt;
|
||||
|
||||
if (isfinite(rate_i) && rate_i > -RATES_I_LIMIT && rate_i < RATES_I_LIMIT &&
|
||||
if (std::isfinite(rate_i) && rate_i > -RATES_I_LIMIT && rate_i < RATES_I_LIMIT &&
|
||||
_att_control(i) > -RATES_I_LIMIT && _att_control(i) < RATES_I_LIMIT) {
|
||||
_rates_int(i) = rate_i;
|
||||
}
|
||||
|
@ -858,10 +859,10 @@ MulticopterAttitudeControl::task_main()
|
|||
control_attitude_rates(dt);
|
||||
|
||||
/* publish actuator controls */
|
||||
_actuators.control[0] = (isfinite(_att_control(0))) ? _att_control(0) : 0.0f;
|
||||
_actuators.control[1] = (isfinite(_att_control(1))) ? _att_control(1) : 0.0f;
|
||||
_actuators.control[2] = (isfinite(_att_control(2))) ? _att_control(2) : 0.0f;
|
||||
_actuators.control[3] = (isfinite(_thrust_sp)) ? _thrust_sp : 0.0f;
|
||||
_actuators.control[0] = (std::isfinite(_att_control(0))) ? _att_control(0) : 0.0f;
|
||||
_actuators.control[1] = (std::isfinite(_att_control(1))) ? _att_control(1) : 0.0f;
|
||||
_actuators.control[2] = (std::isfinite(_att_control(2))) ? _att_control(2) : 0.0f;
|
||||
_actuators.control[3] = (std::isfinite(_thrust_sp)) ? _thrust_sp : 0.0f;
|
||||
_actuators.timestamp = hrt_absolute_time();
|
||||
_actuators.timestamp_sample = _v_att.timestamp;
|
||||
|
||||
|
@ -909,7 +910,7 @@ MulticopterAttitudeControl::start()
|
|||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
1600,
|
||||
(main_t)&MulticopterAttitudeControl::task_main_trampoline,
|
||||
(px4_main_t)&MulticopterAttitudeControl::task_main_trampoline,
|
||||
nullptr);
|
||||
|
||||
if (_control_task < 0) {
|
||||
|
|
|
@ -71,7 +71,7 @@
|
|||
/**
|
||||
* Array of static parameter info.
|
||||
*/
|
||||
#if defined(_UNIT_TEST) || defined(__PX4_LINUX)
|
||||
#if defined(_UNIT_TEST)
|
||||
extern struct param_info_s param_array[];
|
||||
extern struct param_info_s *param_info_base;
|
||||
extern struct param_info_s *param_info_limit;
|
||||
|
|
Loading…
Reference in New Issue