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); } }
int ver_main(int argc, char *argv[]) { /* defaults to an error */ int ret = 1; /* first check if there are at least 2 params */ if (argc >= 2) { if (argv[1] != NULL) { if (!strncmp(argv[1], sz_ver_hwcmp_str, sizeof(sz_ver_hwcmp_str))) { if (argc >= 3 && argv[2] != NULL) { /* compare 3rd parameter with HW_ARCH string, in case of match, return 0 */ ret = strncmp(HW_ARCH, argv[2], strlen(HW_ARCH)); if (ret == 0) { PX4_INFO("match: %s", HW_ARCH); } return ret; } else { warn("Not enough arguments, try 'ver hwcmp PX4FMU_V2'"); return 1; } } /* check if we want to show all */ bool show_all = !strncmp(argv[1], sz_ver_all_str, sizeof(sz_ver_all_str)); if (show_all || !strncmp(argv[1], sz_ver_hw_str, sizeof(sz_ver_hw_str))) { printf("HW arch: %s\n", HW_ARCH); ret = 0; } 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); 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)); ret = 0; } if (show_all || !strncmp(argv[1], sz_ver_bdate_str, sizeof(sz_ver_bdate_str))) { printf("Build datetime: %s %s\n", __DATE__, __TIME__); ret = 0; } if (show_all || !strncmp(argv[1], sz_ver_gcc_str, sizeof(sz_ver_gcc_str))) { printf("Toolchain: %s\n", __VERSION__); ret = 0; } if (show_all || !strncmp(argv[1], mcu_ver_str, sizeof(mcu_ver_str))) { char rev; char *revstr; int chip_version = mcu_version(&rev, &revstr); if (chip_version < 0) { printf("UNKNOWN MCU\n"); } else { printf("MCU: %s, rev. %c\n", revstr, rev); if (chip_version < MCU_REV_STM32F4_REV_3) { printf("\nWARNING WARNING WARNING!\n" "Revision %c has a silicon errata\n" "This device can only utilize a maximum of 1MB flash safely!\n" "https://pixhawk.org/help/errata\n\n", rev); } } ret = 0; } if (show_all || !strncmp(argv[1], mcu_uid_str, sizeof(mcu_uid_str))) { uint32_t uid[3]; mcu_unique_id(uid); printf("UID: %X:%X:%X \n", uid[0], uid[1], uid[2]); ret = 0; } if (ret == 1) { warn("unknown command.\n"); return 1; } } else {
int ver_main(int argc, char *argv[]) { /* defaults to an error */ int ret = 1; /* first check if there are at least 2 params */ if (argc >= 2) { if (argv[1] != NULL) { if (!strncmp(argv[1], sz_ver_hwcmp_str, sizeof(sz_ver_hwcmp_str))) { if (argc >= 3 && argv[2] != NULL) { /* compare 3rd parameter with HW_ARCH string, in case of match, return 0 */ ret = strncmp(HW_ARCH, argv[2], strlen(HW_ARCH)); if (ret == 0) { printf("ver hwcmp match: %s\n", HW_ARCH); } return ret; } else { warn("Not enough arguments, try 'ver hwcmp PX4FMU_V2'"); return 1; } } /* check if we want to show all */ bool show_all = !strncmp(argv[1], sz_ver_all_str, sizeof(sz_ver_all_str)); if (show_all || !strncmp(argv[1], sz_ver_hw_str, sizeof(sz_ver_hw_str))) { printf("HW arch: %s\n", HW_ARCH); ret = 0; } if (show_all || !strncmp(argv[1], sz_ver_git_str, sizeof(sz_ver_git_str))) { printf("FW git-hash: %s\n", px4_git_version); ret = 0; } if (show_all || !strncmp(argv[1], sz_ver_bdate_str, sizeof(sz_ver_bdate_str))) { printf("Build datetime: %s %s\n", __DATE__, __TIME__); ret = 0; } if (show_all || !strncmp(argv[1], sz_ver_gcc_str, sizeof(sz_ver_gcc_str))) { printf("Toolchain: %s\n", __VERSION__); ret = 0; } if (show_all || !strncmp(argv[1], mcu_ver_str, sizeof(mcu_ver_str))) { char rev; char* revstr; int chip_version = mcu_version(&rev, &revstr); if (chip_version < 0) { printf("UNKNOWN MCU\n"); } else { printf("MCU: %s, rev. %c\n", revstr, rev); if (chip_version < MCU_REV_STM32F4_REV_3) { printf("\nWARNING WARNING WARNING!\n" "Revision %c has a silicon errata\n" "This device can only utilize a maximum of 1MB flash safely!\n" "http://px4.io/help/errata\n\n", rev); } } ret = 0; } if (show_all || !strncmp(argv[1], mcu_uid_str, sizeof(mcu_uid_str))) { uint32_t uid[3]; mcu_unique_id(uid); printf("UID: %X:%X:%X \n",uid[0],uid[1],uid[2]); ret = 0; } if (ret == 1) { warn("unknown command.\n"); return 1; } } else { usage("Error, input parameter NULL.\n"); } } else { usage("Error, not enough parameters."); } return ret; }