forked from Archive/PX4-Autopilot
version cleanup: move all version information into version.c and use a common API
The provided versioning information is the same, except for some additions, like OS version (which still need to be implemented on NuttX).
This commit is contained in:
parent
08dc3decb1
commit
41dc34204c
|
@ -101,6 +101,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/rc
|
||||
platforms/nuttx
|
||||
|
|
|
@ -143,6 +143,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
|
|
|
@ -97,6 +97,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
|
|
|
@ -148,6 +148,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
|
|
|
@ -118,6 +118,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
|
|
|
@ -144,6 +144,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
|
|
|
@ -144,6 +144,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
|
|
|
@ -149,6 +149,7 @@ set(config_module_list
|
|||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/terrain_estimation
|
||||
lib/version
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
|
|
|
@ -148,6 +148,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
|
|
|
@ -97,11 +97,12 @@ set(config_module_list
|
|||
lib/geo_lookup
|
||||
lib/conversion
|
||||
lib/launchdetection
|
||||
lib/terrain_estimation
|
||||
lib/rc
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/terrain_estimation
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
lib/rc
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
|
|
|
@ -89,6 +89,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
|
|
|
@ -45,6 +45,7 @@ set(config_module_list
|
|||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/conversion
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
|
||||
platforms/common
|
||||
|
|
|
@ -69,6 +69,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
|
||||
platforms/common
|
||||
|
|
|
@ -91,6 +91,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
|
|
|
@ -69,6 +69,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
|
||||
platforms/common
|
||||
|
|
|
@ -71,6 +71,7 @@ set(config_module_list
|
|||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/terrain_estimation
|
||||
lib/version
|
||||
|
||||
examples/px4_simple_app
|
||||
examples/mc_att_control_multiplatform
|
||||
|
|
|
@ -26,6 +26,7 @@ set(config_module_list
|
|||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
)
|
||||
|
||||
|
|
|
@ -69,6 +69,7 @@ set(config_module_list
|
|||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/controllib
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
|
|
|
@ -92,6 +92,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
|
|
|
@ -43,6 +43,7 @@ set(config_module_list
|
|||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/conversion
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
|
|
|
@ -75,6 +75,7 @@ set(config_module_list
|
|||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
|
|
|
@ -87,6 +87,7 @@ set(config_module_list
|
|||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/rc
|
||||
lib/version
|
||||
lib/DriverFramework/framework
|
||||
|
||||
#
|
||||
|
|
|
@ -0,0 +1,41 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2016 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.
|
||||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE lib__version
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
version.c
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
|
@ -0,0 +1,258 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016 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 "version.h"
|
||||
|
||||
#include "build_git_version.h" //generated from build_git_version.h.in
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#if !defined(CONFIG_CDCACM_PRODUCTID)
|
||||
# define CONFIG_CDCACM_PRODUCTID 0
|
||||
#endif
|
||||
|
||||
#if defined(__PX4_LINUX)
|
||||
#include <sys/utsname.h>
|
||||
#endif
|
||||
|
||||
// dev >= 0
|
||||
// alpha >= 64
|
||||
// beta >= 128
|
||||
// release candidate >= 192
|
||||
// release == 255
|
||||
enum FIRMWARE_TYPE {
|
||||
FIRMWARE_TYPE_DEV = 0,
|
||||
FIRMWARE_TYPE_ALPHA = 64,
|
||||
FIRMWARE_TYPE_BETA = 128,
|
||||
FIRMWARE_TYPE_RC = 192,
|
||||
FIRMWARE_TYPE_RELEASE = 255
|
||||
};
|
||||
|
||||
/**
|
||||
* Convert a version tag string to a number
|
||||
* @param tag version tag in one of the following forms:
|
||||
* - dev: v1.4.0rc3-7-g7e282f57
|
||||
* - rc: v1.4.0rc4
|
||||
* - release: v1.4.0
|
||||
* - linux: 7.9.3
|
||||
* @return version in the form 0xAABBCCTT (AA: Major, BB: Minor, CC: Patch, TT Type @see FIRMWARE_TYPE)
|
||||
*/
|
||||
static uint32_t version_tag_to_number(const char *tag)
|
||||
{
|
||||
uint32_t ver = 0;
|
||||
unsigned len = strlen(tag);
|
||||
unsigned mag = 0;
|
||||
int32_t type = -1;
|
||||
unsigned dashcount = 0;
|
||||
|
||||
for (int i = len - 1; i >= 0; i--) {
|
||||
|
||||
if (tag[i] == '-') {
|
||||
dashcount++;
|
||||
}
|
||||
|
||||
if (tag[i] >= '0' && tag[i] <= '9') {
|
||||
if (mag < 32) {
|
||||
unsigned number = tag[i] - '0';
|
||||
|
||||
ver += (number << mag);
|
||||
mag += 8;
|
||||
}
|
||||
|
||||
} else if (tag[i] == '.') {
|
||||
continue;
|
||||
|
||||
} else if (i > 3 && type == -1) {
|
||||
/* scan and look for signature characters for each type */
|
||||
const char *curr = &tag[i - 1];
|
||||
|
||||
while (curr > &tag[0]) {
|
||||
if (*curr == 'v') {
|
||||
type = FIRMWARE_TYPE_DEV;
|
||||
break;
|
||||
|
||||
} else if (*curr == 'p') {
|
||||
type = FIRMWARE_TYPE_ALPHA;
|
||||
break;
|
||||
|
||||
} else if (*curr == 't') {
|
||||
type = FIRMWARE_TYPE_BETA;
|
||||
break;
|
||||
|
||||
} else if (*curr == 'r') {
|
||||
type = FIRMWARE_TYPE_RC;
|
||||
break;
|
||||
}
|
||||
|
||||
curr--;
|
||||
}
|
||||
|
||||
/* looks like a release */
|
||||
if (type == -1) {
|
||||
type = FIRMWARE_TYPE_RELEASE;
|
||||
}
|
||||
|
||||
} else if (tag[i] != 'v') {
|
||||
/* reset, because we don't have a full tag but
|
||||
* are seeing non-numeric characters (eg. '-')
|
||||
*/
|
||||
ver = 0;
|
||||
mag = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/* if git describe contains dashes this is not a real tag */
|
||||
if (dashcount > 0) {
|
||||
type = FIRMWARE_TYPE_DEV;
|
||||
}
|
||||
|
||||
/* looks like a release */
|
||||
if (type == -1) {
|
||||
type = FIRMWARE_TYPE_RELEASE;
|
||||
}
|
||||
|
||||
ver = (ver << 8);
|
||||
|
||||
return ver | type;
|
||||
}
|
||||
|
||||
|
||||
uint32_t px4_firmware_version(void)
|
||||
{
|
||||
return version_tag_to_number(PX4_GIT_TAG_STR);
|
||||
}
|
||||
|
||||
uint32_t px4_board_version(void)
|
||||
{
|
||||
#if defined(__PX4_NUTTX)
|
||||
return CONFIG_CDCACM_PRODUCTID;
|
||||
#else
|
||||
return 1;
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t px4_os_version(void)
|
||||
{
|
||||
#if defined(__PX4_DARWIN)
|
||||
return 0; //TODO: implement version for Darwin
|
||||
#elif defined(__PX4_LINUX)
|
||||
struct utsname name;
|
||||
|
||||
if (uname(&name) == 0) {
|
||||
char *c = name.release;
|
||||
|
||||
// cut the part after the first '-'
|
||||
while (*c && *c != '-') {
|
||||
++c;
|
||||
}
|
||||
|
||||
*c = 0;
|
||||
return version_tag_to_number(name.release);
|
||||
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
|
||||
#elif defined(__PX4_QURT)
|
||||
return 0; //TODO: implement version for QuRT
|
||||
#elif defined(__PX4_NUTTX)
|
||||
return version_tag_to_number("v7.18.0"); //TODO: get correct version
|
||||
#else
|
||||
# error "px4_os_version not implemented for current OS"
|
||||
#endif
|
||||
}
|
||||
|
||||
const char *px4_os_version_string(void)
|
||||
{
|
||||
#if defined(__PX4_NUTTX)
|
||||
return NULL; //TODO: get NuttX git tag as string
|
||||
#else
|
||||
return NULL;
|
||||
#endif
|
||||
}
|
||||
|
||||
const char *px4_os_name(void)
|
||||
{
|
||||
#if defined(__PX4_DARWIN)
|
||||
return "Darwin";
|
||||
#elif defined(__PX4_LINUX)
|
||||
return "Linux";
|
||||
#elif defined(__PX4_QURT)
|
||||
return "QuRT";
|
||||
#elif defined(__PX4_NUTTX)
|
||||
return "NuttX";
|
||||
#else
|
||||
# error "px4_os_name not implemented for current OS"
|
||||
#endif
|
||||
}
|
||||
|
||||
const char *px4_toolchain_name(void)
|
||||
{
|
||||
#if defined(__clang__)
|
||||
return "Clang/LLVM";
|
||||
#elif defined(__ICC) || defined(__INTEL_COMPILER)
|
||||
return "Intel ICC";
|
||||
#elif defined(__GNUC__) || defined(__GNUG__)
|
||||
return "GNU GCC";
|
||||
#elif defined(_MSC_VER)
|
||||
return "MS Visual Studio";
|
||||
#else
|
||||
return "Unknown";
|
||||
#endif
|
||||
}
|
||||
|
||||
const char *px4_toolchain_version(void)
|
||||
{
|
||||
#ifdef __VERSION__
|
||||
return __VERSION__;
|
||||
#else
|
||||
return "";
|
||||
#endif
|
||||
}
|
||||
|
||||
const char *px4_firmware_version_string(void)
|
||||
{
|
||||
return PX4_GIT_VERSION_STR;
|
||||
}
|
||||
|
||||
uint64_t px4_firmware_version_binary(void)
|
||||
{
|
||||
return PX4_GIT_VERSION_BINARY;
|
||||
}
|
||||
|
||||
uint64_t px4_os_version_binary(void)
|
||||
{
|
||||
//TODO: get NuttX version via git tag
|
||||
return 0;
|
||||
}
|
||||
|
|
@ -38,10 +38,12 @@
|
|||
* Tools for system version detection.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
* @author Beat Küng <beat-kueng@gmx.net>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#define FREEZE_STR(s) #s
|
||||
#define STRINGIFY(s) FREEZE_STR(s)
|
||||
|
@ -79,7 +81,60 @@ static inline const char *px4_board_name(void)
|
|||
return BOARD_NAME;
|
||||
}
|
||||
|
||||
/**
|
||||
* get the PX4 Firmware version
|
||||
* @return version in the form 0xAABBCCTT (AA: Major, BB: Minor, CC: Patch, TT Type @see FIRMWARE_TYPE)
|
||||
*/
|
||||
__EXPORT uint32_t px4_firmware_version(void);
|
||||
|
||||
/**
|
||||
* get the board version (last 8 bytes should be silicon ID, if any)
|
||||
*/
|
||||
__EXPORT uint32_t px4_board_version(void);
|
||||
|
||||
/**
|
||||
* operating system version
|
||||
* @return version in the form 0xAABBCCTT (AA: Major, BB: Minor, CC: Patch, TT Type @see FIRMWARE_TYPE)
|
||||
*/
|
||||
__EXPORT uint32_t px4_os_version(void);
|
||||
|
||||
/**
|
||||
* Operating system version as human readable string (git tag)
|
||||
* @return string or NULL if not defined
|
||||
*/
|
||||
__EXPORT const char *px4_os_version_string(void);
|
||||
|
||||
/**
|
||||
* name of the operating system
|
||||
* @return human readable string
|
||||
*/
|
||||
__EXPORT const char *px4_os_name(void);
|
||||
|
||||
/**
|
||||
* Toolchain name used to compile PX4
|
||||
*/
|
||||
__EXPORT const char *px4_toolchain_name(void);
|
||||
|
||||
/**
|
||||
* Toolchain version used to compile PX4 (no particular format)
|
||||
*/
|
||||
__EXPORT const char *px4_toolchain_version(void);
|
||||
|
||||
/**
|
||||
* Firmware version as human readable string (git tag)
|
||||
*/
|
||||
__EXPORT const char *px4_firmware_version_string(void);
|
||||
|
||||
/**
|
||||
* Firmware version in binary form (first part of the git tag)
|
||||
*/
|
||||
__EXPORT uint64_t px4_firmware_version_binary(void);
|
||||
|
||||
/**
|
||||
* Operating system version in binary form (first part of the git tag)
|
||||
* @return this is not available on all OSes and can return 0
|
||||
*/
|
||||
__EXPORT uint64_t px4_os_version_binary(void);
|
||||
|
||||
__END_DECLS
|
||||
|
||||
|
|
|
@ -1361,7 +1361,7 @@ void Logger::write_header()
|
|||
/* write version info messages */
|
||||
void Logger::write_version()
|
||||
{
|
||||
write_info("ver_sw", PX4_GIT_VERSION_STR);
|
||||
write_info("ver_sw", px4_firmware_version_string());
|
||||
write_info("ver_hw", px4_board_name());
|
||||
write_info("sys_name", "PX4");
|
||||
int32_t utc_offset = 0;
|
||||
|
|
|
@ -39,7 +39,6 @@
|
|||
#include <drivers/drv_hrt.h>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <version/version.h>
|
||||
#include <systemlib/git_version.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
extern "C" __EXPORT int logger_main(int argc, char *argv[]);
|
||||
|
|
|
@ -72,11 +72,10 @@
|
|||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/mcu_version.h>
|
||||
#include <systemlib/git_version.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <geo/geo.h>
|
||||
#include <dataman/dataman.h>
|
||||
//#include <mathlib/mathlib.h>
|
||||
#include <version/version.h>
|
||||
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/vehicle_command_ack.h>
|
||||
|
@ -1283,13 +1282,15 @@ void Mavlink::send_autopilot_capabilites()
|
|||
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED;
|
||||
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET;
|
||||
msg.capabilities |= MAV_PROTOCOL_CAPABILITY_MAVLINK2;
|
||||
msg.flight_sw_version = version_tag_to_number(px4_git_tag);
|
||||
msg.middleware_sw_version = version_tag_to_number(px4_git_tag);
|
||||
msg.os_sw_version = version_tag_to_number(os_git_tag);
|
||||
msg.board_version = px4_board_version;
|
||||
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));
|
||||
msg.flight_sw_version = px4_firmware_version();
|
||||
msg.middleware_sw_version = px4_firmware_version();
|
||||
msg.os_sw_version = px4_os_version();
|
||||
msg.board_version = px4_board_version();
|
||||
uint64_t fw_git_version_binary = px4_firmware_version_binary();
|
||||
memcpy(&msg.flight_custom_version, &fw_git_version_binary, sizeof(msg.flight_custom_version));
|
||||
memcpy(&msg.middleware_custom_version, &fw_git_version_binary, sizeof(msg.middleware_custom_version));
|
||||
uint64_t os_git_version_binary = px4_os_version_binary();
|
||||
memcpy(&msg.os_custom_version, &os_git_version_binary, sizeof(msg.os_custom_version));
|
||||
#ifdef CONFIG_CDCACM_VENDORID
|
||||
msg.vendor_id = CONFIG_CDCACM_VENDORID;
|
||||
#else
|
||||
|
|
|
@ -116,7 +116,6 @@
|
|||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/git_version.h>
|
||||
#include <systemlib/printload.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <version/version.h>
|
||||
|
@ -873,7 +872,7 @@ int write_version(int fd)
|
|||
};
|
||||
|
||||
/* fill version message and write it */
|
||||
strncpy(log_msg_VER.body.fw_git, px4_git_version, sizeof(log_msg_VER.body.fw_git));
|
||||
strncpy(log_msg_VER.body.fw_git, px4_firmware_version_string(), sizeof(log_msg_VER.body.fw_git));
|
||||
strncpy(log_msg_VER.body.arch, px4_board_name(), sizeof(log_msg_VER.body.arch));
|
||||
return write(fd, &log_msg_VER, sizeof(log_msg_VER));
|
||||
}
|
||||
|
|
|
@ -1,56 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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>
|
||||
|
||||
#include "build_git_version.h"
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
__EXPORT extern const char *px4_git_version;
|
||||
__EXPORT extern const uint64_t px4_git_version_binary;
|
||||
__EXPORT extern const char *px4_git_tag;
|
||||
__EXPORT extern const char *os_git_tag;
|
||||
__EXPORT extern const uint32_t px4_board_version;
|
||||
|
||||
__EXPORT uint32_t version_tag_to_number(const char *tag);
|
||||
|
||||
__END_DECLS
|
|
@ -60,7 +60,7 @@ __EXPORT void mcu_unique_id(uint32_t *uid_96_bit);
|
|||
*
|
||||
* @param rev The silicon revision character
|
||||
* @param revstr The full chip name string
|
||||
* @return The silicon revision / version number as integer
|
||||
* @return The silicon revision / version number as integer. -1 on error (rev and revstr will not be set)
|
||||
*/
|
||||
__EXPORT int mcu_version(char *rev, char **revstr);
|
||||
|
||||
|
|
|
@ -53,7 +53,6 @@
|
|||
#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>
|
||||
|
@ -622,7 +621,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, px4_git_version, 8);
|
||||
std::memmove(fw_git_short, px4_firmware_version_string(), 8);
|
||||
assert(fw_git_short[8] == '\0');
|
||||
char *end = nullptr;
|
||||
swver.vcs_commit = std::strtol(fw_git_short, &end, 16);
|
||||
|
|
|
@ -45,7 +45,6 @@
|
|||
#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>
|
||||
|
|
|
@ -46,7 +46,6 @@
|
|||
#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";
|
||||
|
@ -59,123 +58,6 @@ static const char sz_ver_all_str[] = "all";
|
|||
static const char mcu_ver_str[] = "mcu";
|
||||
static const char mcu_uid_str[] = "uid";
|
||||
|
||||
const char *px4_git_version = PX4_GIT_VERSION_STR;
|
||||
const uint64_t px4_git_version_binary = PX4_GIT_VERSION_BINARY;
|
||||
#if !defined(CONFIG_CDCACM_PRODUCTID)
|
||||
# define CONFIG_CDCACM_PRODUCTID 0
|
||||
#endif
|
||||
const char *px4_git_tag = PX4_GIT_TAG_STR;
|
||||
|
||||
#if defined(__PX4_NUTTX)
|
||||
__EXPORT const char *os_git_tag = "7.18";
|
||||
__EXPORT const uint32_t px4_board_version = CONFIG_CDCACM_PRODUCTID;
|
||||
#else
|
||||
__EXPORT const char *os_git_tag = "";
|
||||
__EXPORT const uint32_t px4_board_version = 1;
|
||||
#endif
|
||||
|
||||
// dev >= 0
|
||||
// alpha >= 64
|
||||
// beta >= 128
|
||||
// release candidate >= 192
|
||||
// release == 255
|
||||
enum FIRMWARE_TYPE {
|
||||
FIRMWARE_TYPE_DEV = 0,
|
||||
FIRMWARE_TYPE_ALPHA = 64,
|
||||
FIRMWARE_TYPE_BETA = 128,
|
||||
FIRMWARE_TYPE_RC = 192,
|
||||
FIRMWARE_TYPE_RELEASE = 255
|
||||
};
|
||||
|
||||
/**
|
||||
* Convert a version tag string to a number
|
||||
*/
|
||||
uint32_t version_tag_to_number(const char *tag)
|
||||
{
|
||||
uint32_t ver = 0;
|
||||
unsigned len = strlen(tag);
|
||||
unsigned mag = 0;
|
||||
int32_t type = -1;
|
||||
bool dotparsed = false;
|
||||
unsigned dashcount = 0;
|
||||
|
||||
for (int i = len - 1; i >= 0; i--) {
|
||||
|
||||
if (tag[i] == '-') {
|
||||
dashcount++;
|
||||
}
|
||||
|
||||
if (tag[i] >= '0' && tag[i] <= '9') {
|
||||
unsigned number = tag[i] - '0';
|
||||
|
||||
ver += (number << mag);
|
||||
mag += 8;
|
||||
|
||||
} else if (tag[i] == '.') {
|
||||
continue;
|
||||
|
||||
} else if (mag > 2 * 8 && dotparsed) {
|
||||
/* this is a full version and we have enough digits */
|
||||
return ver;
|
||||
|
||||
} else if (i > 3 && type == -1) {
|
||||
/* scan and look for signature characters for each type */
|
||||
const char *curr = &tag[i - 1];
|
||||
|
||||
// dev: v1.4.0rc3-7-g7e282f57
|
||||
// rc: v1.4.0rc4
|
||||
// release: v1.4.0
|
||||
|
||||
while (curr > &tag[0]) {
|
||||
if (*curr == 'v') {
|
||||
type = FIRMWARE_TYPE_DEV;
|
||||
break;
|
||||
|
||||
} else if (*curr == 'p') {
|
||||
type = FIRMWARE_TYPE_ALPHA;
|
||||
break;
|
||||
|
||||
} else if (*curr == 't') {
|
||||
type = FIRMWARE_TYPE_BETA;
|
||||
break;
|
||||
|
||||
} else if (*curr == 'r') {
|
||||
type = FIRMWARE_TYPE_RC;
|
||||
break;
|
||||
}
|
||||
|
||||
curr--;
|
||||
}
|
||||
|
||||
/* looks like a release */
|
||||
if (type == -1) {
|
||||
type = FIRMWARE_TYPE_RELEASE;
|
||||
}
|
||||
|
||||
} else if (tag[i] != 'v') {
|
||||
/* reset, because we don't have a full tag but
|
||||
* are seeing non-numeric characters
|
||||
*/
|
||||
ver = 0;
|
||||
mag = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/* if git describe contains dashes this is not a real tag */
|
||||
if (dashcount > 0) {
|
||||
type = FIRMWARE_TYPE_DEV;
|
||||
}
|
||||
|
||||
/* looks like a release */
|
||||
if (type == -1) {
|
||||
type = FIRMWARE_TYPE_RELEASE;
|
||||
}
|
||||
|
||||
ver = (ver << 8);
|
||||
|
||||
return ver | type;
|
||||
}
|
||||
|
||||
static void usage(const char *reason)
|
||||
{
|
||||
if (reason != NULL) {
|
||||
|
@ -224,16 +106,41 @@ 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", px4_git_version);
|
||||
unsigned fwver = version_tag_to_number(px4_git_tag);
|
||||
printf("FW git-hash: %s\n", px4_firmware_version_string());
|
||||
unsigned fwver = px4_firmware_version();
|
||||
unsigned major = (fwver >> (8 * 3)) & 0xFF;
|
||||
unsigned minor = (fwver >> (8 * 2)) & 0xFF;
|
||||
unsigned patch = (fwver >> (8 * 1)) & 0xFF;
|
||||
unsigned type = (fwver >> (8 * 0)) & 0xFF;
|
||||
printf("FW version: %s (%u.%u.%u %u), %u\n", px4_git_tag, major, minor, patch,
|
||||
type, fwver);
|
||||
/* middleware is currently the same thing as firmware, so not printing yet */
|
||||
printf("OS version: %s (%u)\n", os_git_tag, version_tag_to_number(os_git_tag));
|
||||
|
||||
if (type == 255) {
|
||||
printf("FW version: Release %u.%u.%u (%u)\n", major, minor, patch, fwver);
|
||||
|
||||
} else {
|
||||
printf("FW version: %u.%u.%u %u (%u)\n", major, minor, patch, type, fwver);
|
||||
}
|
||||
|
||||
|
||||
fwver = px4_os_version();
|
||||
major = (fwver >> (8 * 3)) & 0xFF;
|
||||
minor = (fwver >> (8 * 2)) & 0xFF;
|
||||
patch = (fwver >> (8 * 1)) & 0xFF;
|
||||
type = (fwver >> (8 * 0)) & 0xFF;
|
||||
printf("OS: %s\n", px4_os_name());
|
||||
|
||||
if (type == 255) {
|
||||
printf("OS version: Release %u.%u.%u (%u)\n", major, minor, patch, fwver);
|
||||
|
||||
} else {
|
||||
printf("OS version: %u.%u.%u %u (%u)\n", major, minor, patch, type, fwver);
|
||||
}
|
||||
|
||||
const char *os_git_hash = px4_os_version_string();
|
||||
|
||||
if (os_git_hash) {
|
||||
printf("OS git-hash: %s\n", os_git_hash);
|
||||
}
|
||||
|
||||
ret = 0;
|
||||
|
||||
}
|
||||
|
@ -252,7 +159,7 @@ int ver_main(int argc, char *argv[])
|
|||
|
||||
|
||||
if (show_all || !strncmp(argv[1], sz_ver_gcc_str, sizeof(sz_ver_gcc_str))) {
|
||||
printf("Toolchain: %s\n", __VERSION__);
|
||||
printf("Toolchain: %s, %s\n", px4_toolchain_name(), px4_toolchain_version());
|
||||
ret = 0;
|
||||
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue