forked from Archive/PX4-Autopilot
Merged release_v1.0.0 into master
This commit is contained in:
commit
8fd00f4d6d
7
Makefile
7
Makefile
|
@ -55,7 +55,12 @@ GIT_DESC := $(shell git log -1 --pretty=format:%H)
|
|||
ifneq ($(words $(GIT_DESC)),1)
|
||||
GIT_DESC := "unknown_git_version"
|
||||
endif
|
||||
export GIT_DESC
|
||||
|
||||
GIT_DESC_SHORT := $(shell echo $(GIT_DESC) | cut -c1-16)
|
||||
|
||||
$(shell echo "#include <systemlib/git_version.h>" > $(BUILD_DIR)git_version.c)
|
||||
$(shell echo "const char* px4_git_version = \"$(GIT_DESC)\";" >> $(BUILD_DIR)git_version.c)
|
||||
$(shell echo "const uint64_t px4_git_version_binary = 0x$(GIT_DESC_SHORT);" >> $(BUILD_DIR)git_version.c)
|
||||
|
||||
#
|
||||
# Canned firmware configurations that we (know how to) build.
|
||||
|
|
|
@ -69,6 +69,8 @@
|
|||
#include <systemlib/err.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/mcu_version.h>
|
||||
#include <systemlib/git_version.h>
|
||||
#include <geo/geo.h>
|
||||
#include <dataman/dataman.h>
|
||||
//#include <mathlib/mathlib.h>
|
||||
|
@ -949,6 +951,47 @@ Mavlink::send_statustext(unsigned char severity, const char *string)
|
|||
mavlink_logbuffer_write(&_logbuffer, &logmsg);
|
||||
}
|
||||
|
||||
void Mavlink::send_autopilot_capabilites() {
|
||||
struct vehicle_status_s status;
|
||||
|
||||
MavlinkOrbSubscription *status_sub = this->add_orb_subscription(ORB_ID(vehicle_status));
|
||||
|
||||
if (status_sub->update(&status)) {
|
||||
mavlink_autopilot_version_t msg = {};
|
||||
|
||||
msg.capabilities = MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
|
||||
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT;
|
||||
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_COMMAND_INT;
|
||||
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_FTP;
|
||||
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_FTP;
|
||||
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET;
|
||||
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED;
|
||||
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET;
|
||||
msg.flight_sw_version = 0;
|
||||
msg.middleware_sw_version = 0;
|
||||
msg.os_sw_version = 0;
|
||||
msg.board_version = 0;
|
||||
memcpy(&msg.flight_custom_version, &px4_git_version_binary, sizeof(msg.flight_custom_version));
|
||||
memcpy(&msg.middleware_custom_version, &px4_git_version_binary, sizeof(msg.middleware_custom_version));
|
||||
memset(&msg.os_custom_version, 0, sizeof(msg.os_custom_version));
|
||||
#ifdef CONFIG_CDCACM_VENDORID
|
||||
msg.vendor_id = CONFIG_CDCACM_VENDORID;
|
||||
#else
|
||||
msg.vendor_id = 0;
|
||||
#endif
|
||||
#ifdef CONFIG_CDCACM_PRODUCTID
|
||||
msg.product_id = CONFIG_CDCACM_PRODUCTID;
|
||||
#else
|
||||
msg.product_id = 0;
|
||||
#endif
|
||||
uint32_t uid[3];
|
||||
mcu_unique_id(uid);
|
||||
msg.uid = (((uint64_t)uid[1]) << 32) | uid[2];
|
||||
|
||||
this->send_message(MAVLINK_MSG_ID_AUTOPILOT_VERSION, &msg);
|
||||
}
|
||||
}
|
||||
|
||||
MavlinkOrbSubscription *Mavlink::add_orb_subscription(const orb_id_t topic, int instance)
|
||||
{
|
||||
/* check if already subscribed to this topic */
|
||||
|
@ -1482,6 +1525,8 @@ Mavlink::task_main(int argc, char *argv[])
|
|||
/* now the instance is fully initialized and we can bump the instance count */
|
||||
LL_APPEND(_mavlink_instances, this);
|
||||
|
||||
send_autopilot_capabilites();
|
||||
|
||||
while (!_task_should_exit) {
|
||||
/* main loop */
|
||||
usleep(_main_loop_delay);
|
||||
|
|
|
@ -241,6 +241,7 @@ public:
|
|||
* @param severity the log level
|
||||
*/
|
||||
void send_statustext(unsigned char severity, const char *string);
|
||||
void send_autopilot_capabilites();
|
||||
|
||||
MavlinkStream * get_streams() const { return _streams; }
|
||||
|
||||
|
|
|
@ -280,7 +280,9 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
|
|||
|
||||
/* terminate other threads and this thread */
|
||||
_mavlink->_task_should_exit = true;
|
||||
|
||||
} else if (cmd_mavlink.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
|
||||
/* send autopilot version message */
|
||||
_mavlink->send_autopilot_capabilites();
|
||||
} else {
|
||||
|
||||
if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) {
|
||||
|
|
|
@ -49,5 +49,3 @@ MAXOPTIMIZATION = -Os
|
|||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
EXTRACFLAGS = -Wframe-larger-than=1400
|
||||
endif
|
||||
|
||||
EXTRADEFINES = -DGIT_VERSION='"$(GIT_DESC)"'
|
||||
|
|
|
@ -105,6 +105,7 @@
|
|||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/git_version.h>
|
||||
#include <version/version.h>
|
||||
|
||||
#include <mavlink/mavlink_log.h>
|
||||
|
@ -798,7 +799,7 @@ int write_version(int fd)
|
|||
};
|
||||
|
||||
/* fill version message and write it */
|
||||
strncpy(log_msg_VER.body.fw_git, GIT_VERSION, sizeof(log_msg_VER.body.fw_git));
|
||||
strncpy(log_msg_VER.body.fw_git, px4_git_version, sizeof(log_msg_VER.body.fw_git));
|
||||
strncpy(log_msg_VER.body.arch, HW_ARCH, sizeof(log_msg_VER.body.arch));
|
||||
return write(fd, &log_msg_VER, sizeof(log_msg_VER));
|
||||
}
|
||||
|
|
|
@ -0,0 +1,49 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2015 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 git_version.h
|
||||
*
|
||||
* GIT repository version
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
__EXPORT extern const char* px4_git_version;
|
||||
__EXPORT extern const uint64_t px4_git_version_binary;
|
||||
|
||||
__END_DECLS
|
|
@ -1,6 +1,6 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2012-2015 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
|
||||
|
@ -52,7 +52,8 @@ SRCS = \
|
|||
mcu_version.c \
|
||||
bson/tinybson.c \
|
||||
circuit_breaker.cpp \
|
||||
circuit_breaker_params.c
|
||||
circuit_breaker_params.c \
|
||||
$(BUILD_DIR)git_version.c
|
||||
|
||||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
SRCS += err.c \
|
||||
|
|
|
@ -63,7 +63,7 @@ SRCS += $(subst $(PX4_MODULE_SRC),../../,$(LIBUAVCAN_SRC))
|
|||
INCLUDE_DIRS += $(LIBUAVCAN_INC)
|
||||
# Since actual compiler mode is C++11, the library will default to UAVCAN_CPP11, but it will fail to compile
|
||||
# because this platform lacks most of the standard library and STL. Hence we need to force C++03 mode.
|
||||
override EXTRADEFINES := $(EXTRADEFINES) -DGIT_VERSION='"$(GIT_DESC)"' -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 -DUAVCAN_NO_ASSERTIONS
|
||||
override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 -DUAVCAN_NO_ASSERTIONS
|
||||
|
||||
|
||||
#
|
||||
|
|
|
@ -42,6 +42,7 @@
|
|||
#include <systemlib/mixer/mixer.h>
|
||||
#include <systemlib/board_serial.h>
|
||||
#include <systemlib/scheduling_priorities.h>
|
||||
#include <systemlib/git_version.h>
|
||||
#include <version/version.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <arch/chip/chip.h>
|
||||
|
@ -212,7 +213,7 @@ void UavcanNode::fill_node_info()
|
|||
|
||||
// Extracting the first 8 hex digits of GIT_VERSION and converting them to int
|
||||
char fw_git_short[9] = {};
|
||||
std::memmove(fw_git_short, GIT_VERSION, 8);
|
||||
std::memmove(fw_git_short, px4_git_version, 8);
|
||||
assert(fw_git_short[8] == '\0');
|
||||
char *end = nullptr;
|
||||
swver.vcs_commit = std::strtol(fw_git_short, &end, 16);
|
||||
|
|
|
@ -42,5 +42,3 @@ SRCS = ver.c
|
|||
MODULE_STACKSIZE = 1024
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
EXTRADEFINES = -DGIT_VERSION='"$(GIT_DESC)"'
|
||||
|
|
|
@ -45,6 +45,7 @@
|
|||
#include <version/version.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/mcu_version.h>
|
||||
#include <systemlib/git_version.h>
|
||||
|
||||
/* string constants for version commands */
|
||||
static const char sz_ver_hw_str[] = "hw";
|
||||
|
@ -101,7 +102,7 @@ int ver_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
if (show_all || !strncmp(argv[1], sz_ver_git_str, sizeof(sz_ver_git_str))) {
|
||||
printf("FW git-hash: %s\n", GIT_VERSION);
|
||||
printf("FW git-hash: %s\n", px4_git_version);
|
||||
ret = 0;
|
||||
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue