PX4模块设计之二十七:LandDetector模块

2023-05-16

PX4模块设计之二十七:LandDetector模块

  • 1. LandDetector模块简介
  • 2. 模块入口函数
    • 2.1 主入口land_detector_main
    • 2.2 自定义子命令custom_command
  • 3. LandDetector模块重要函数
    • 3.1 task_spawn
      • 3.1.1 FixedwingLandDetector
      • 3.1.2 MulticopterLandDetector
      • 3.1.3 VtolLandDetector
      • 3.1.4 RoverLandDetector
      • 3.1.5 AirshipLandDetector
    • 3.2 instantiate
    • 3.3 start
    • 3.4 Run
  • 4. 总结
  • 5. 参考资料

1. LandDetector模块简介

支持多种机型:

  1. 固定翼:fixedwing
  2. 多旋翼:multicopter
  3. 垂直起降:vtol
  4. 车辆:rover
  5. 飞艇:airship

注:模块仅支持start/stop/status命令。

### Description

Module to detect the freefall and landed state of the vehicle, and publishing the `vehicle_land_detected` topic.
Each vehicle type (multirotor, fixedwing, vtol, ...) provides its own algorithm, taking into account various
states, such as commanded thrust, arming state and vehicle motion.

### Implementation

Every type is implemented in its own class with a common base class. The base class maintains a state (landed,
maybe_landed, ground_contact). Each possible state is implemented in the derived classes. A hysteresis and a fixed
priority of each internal state determines the actual land_detector state.

#### Multicopter Land Detector

**ground_contact**: thrust setpoint and velocity in z-direction must be below a defined threshold for time
GROUND_CONTACT_TRIGGER_TIME_US. When ground_contact is detected, the position controller turns off the thrust setpoint
in body x and y.

**maybe_landed**: it requires ground_contact together with a tighter thrust setpoint threshold and no velocity in the
horizontal direction. The trigger time is defined by MAYBE_LAND_TRIGGER_TIME. When maybe_landed is detected, the
position controller sets the thrust setpoint to zero.

**landed**: it requires maybe_landed to be true for time LAND_DETECTOR_TRIGGER_TIME_US.

The module runs periodically on the HP work queue.

land_detector <command> [arguments...]
 Commands:
   start         Start the background task
     fixedwing|multicopter|vtol|rover|airship Select vehicle type

   stop

   status        print status info

注:print_usage函数是具体对应实现。

class LandDetector : public ModuleBase<LandDetector>, ModuleParams, px4::ScheduledWorkItem

注:LandDetector模块采用了ModuleBase和WorkQueue设计。

2. 模块入口函数

2.1 主入口land_detector_main

同样继承了ModuleBase,由ModuleBase的main来完成模块入口。

land_detector_main
 └──> return LandDetector::main(argc, argv)

2.2 自定义子命令custom_command

模块仅支持start/stop/status命令,不支持其他自定义命令。

LandDetector::custom_command
 └──> return print_usage("unknown command");

3. LandDetector模块重要函数

3.1 task_spawn

不同的机型使用不同的继承LandDetector类进行区分:

  1. 固定翼:fixedwing ───> FixedwingLandDetector
  2. 多旋翼:multicopter ───> MulticopterLandDetector
  3. 垂直起降:vtol ───> VtolLandDetector
  4. 车辆:rover ───> RoverLandDetector
  5. 飞艇:airship ───> AirshipLandDetector

模块使用启动函数LandDetector::start来启动模块。

LandDetector::task_spawn
 ├──> <fixedwing>
 │   └──> obj = new FixedwingLandDetector()
 ├──> <multicopter>
 │   └──> obj = new MulticopterLandDetector()
 ├──> <vtol>
 │   └──> obj = new VtolLandDetector()
 ├──> <rover>
 │   └──> obj = new RoverLandDetector()
 ├──> <airship>
 │   └──> obj = new AirshipLandDetector()
 ├──> <else>
 │   ├──> print_usage("unknown mode")
 │   └──> return PX4_ERROR
 ├──> <obj == nullptr>
 │   ├──> PX4_ERR("alloc failed")
 │   └──> return PX4_ERROR
 ├──> strncpy(_currentMode, argv[1], sizeof(_currentMode) - 1);_currentMode[sizeof(_currentMode) - 1] = '\0'; // Remember current active mode
 ├──> _object.store(obj)
 ├──> _task_id = task_id_is_work_queue
 ├──> obj->start()
 └──> return PX4_OK

注:不同机型的LandDetector继承类,分别重载了各自对应的实现方法。从LandDetector业务框架流程的角度还是在LandDetector::Run中实现。

3.1.1 FixedwingLandDetector

class FixedwingLandDetector final : public LandDetector
{
public:
	FixedwingLandDetector();
	~FixedwingLandDetector() override = default;

protected:

	bool _get_landed_state() override;
	void _set_hysteresis_factor(const int factor) override {};

private:
	... //略
}

3.1.2 MulticopterLandDetector

class MulticopterLandDetector : public LandDetector
{
public:
	MulticopterLandDetector();
	~MulticopterLandDetector() override = default;

protected:
	void _update_params() override;
	void _update_topics() override;

	bool _get_landed_state() override;
	bool _get_ground_contact_state() override;
	bool _get_maybe_landed_state() override;
	bool _get_freefall_state() override;
	bool _get_ground_effect_state() override;
	bool _get_in_descend() override { return _in_descend; }
	bool _get_has_low_throttle() override { return _has_low_throttle; }
	bool _get_horizontal_movement() override { return _horizontal_movement; }
	bool _get_vertical_movement() override { return _vertical_movement; }
	bool _get_close_to_ground_or_skipped_check() override { return _close_to_ground_or_skipped_check; }

	void _set_hysteresis_factor(const int factor) override;

private:
	... //略
}

3.1.3 VtolLandDetector

class VtolLandDetector : public MulticopterLandDetector
{
public:
	VtolLandDetector() = default;
	~VtolLandDetector() override = default;

protected:
	void _update_topics() override;
	bool _get_landed_state() override;
	bool _get_maybe_landed_state() override;
	bool _get_freefall_state() override;

private:
	... //略
}

3.1.4 RoverLandDetector

class RoverLandDetector : public LandDetector
{
public:
	RoverLandDetector() = default;
	~RoverLandDetector() override = default;

protected:
	bool _get_ground_contact_state() override;
	bool _get_landed_state() override;
	void _set_hysteresis_factor(const int factor) override {};
}

3.1.5 AirshipLandDetector

class AirshipLandDetector : public LandDetector
{
public:
	AirshipLandDetector() = default;
	~AirshipLandDetector() override = default;

protected:
	bool _get_ground_contact_state() override;
	bool _get_landed_state() override;
	void _set_hysteresis_factor(const int factor) override {};
};

3.2 instantiate

注:鉴于该模块不采用任务(线程),所以ModuleBase::run_trampoline无需执行,所以可以不实现。

3.3 start

LandDetector::start
 ├──> ScheduleDelayed(50_ms)    // 默认50ms进行一次ScheduleNow
 └──> _vehicle_local_position_sub.registerCallback()  //飞行器位置消息发布时,回调一次ScheduleNow

注:位置发生改变直接回调ScheduleNow,从而触发LandDetector::Run。

uORB::SubscriptionCallbackWorkItem _vehicle_local_position_sub{this, ORB_ID(vehicle_local_position)};

3.4 Run

LandDetector业务监测框架代码(飞行器位置发生改变或者50ms定时间隔轮询)实现逻辑流程如下所示:

LandDetector::Run
 ├──> ScheduleDelayed(50_ms)  // push backup schedule, 定时延期(当没有其他消息回调时)
 ├──> perf_begin(_cycle_perf)
 │ 
 ├──> <_parameter_update_sub.updated() || (_land_detected.timestamp == 0)>
 │   ├──> _parameter_update_sub.copy(&param_update)
 │   ├──> updateParams()
 │   ├──> 【可重载】_update_params()
 │   ├──> _total_flight_time = static_cast<uint64_t>(_param_total_flight_time_high.get()) << 32
 │   └──> _total_flight_time |= static_cast<uint32_t>(_param_total_flight_time_low.get())
 │ 
 ├──> <_actuator_armed_sub.update(&actuator_armed)>
 │   └──> _armed = actuator_armed.armed
 ├──> <_vehicle_acceleration_sub.update(&vehicle_acceleration)>
 │   └──> _acceleration = matrix::Vector3f{vehicle_acceleration.xyz}
 ├──> <_vehicle_angular_velocity_sub.update(&vehicle_angular_velocity)>
 │   ├──> _angular_velocity = matrix::Vector3f{vehicle_angular_velocity.xyz}
 │   ├──> static constexpr float GYRO_NORM_MAX = math::radians(3.f); // 3 degrees/second
 │   └──> <_angular_velocity.norm() > GYRO_NORM_MAX>
 │       └──> _time_last_move_detect_us = vehicle_angular_velocity.timestamp_sample
 │
 ├──> _vehicle_local_position_sub.update(&_vehicle_local_position)
 ├──> _vehicle_status_sub.update(&_vehicle_status)
 ├──> 【可重载】_update_topics()
 ├──> <!_dist_bottom_is_observable>
 │   └──> _dist_bottom_is_observable = _vehicle_local_position.dist_bottom_sensor_bitfield & vehicle_local_position_s::DIST_BOTTOM_SENSOR_RANGE; // we consider the distance to the ground observable if the system is using a range sensor
 ├──> <_dist_bottom_is_observable && !_vehicle_local_position.dist_bottom_valid>
 │   └──> _set_hysteresis_factor(3)
 ├──> <else>
 │   └──> _set_hysteresis_factor(1)
 │   【开始LandDetector状态判断】
 ├──> const hrt_abstime now_us = hrt_absolute_time();
 ├──> _freefall_hysteresis.set_state_and_update(【可重载】_get_freefall_state(), now_us);
 ├──> _ground_contact_hysteresis.set_state_and_update(【可重载】_get_ground_contact_state(), now_us);
 ├──> _maybe_landed_hysteresis.set_state_and_update(【可重载】_get_maybe_landed_state(), now_us);
 ├──> _landed_hysteresis.set_state_and_update(【可重载】_get_landed_state(), now_us);
 ├──> _ground_effect_hysteresis.set_state_and_update(【可重载】_get_ground_effect_state(), now_us);
 │   【获取LandDetector状态】
 ├──> const bool freefallDetected = _freefall_hysteresis.get_state();
 ├──> const bool ground_contactDetected = _ground_contact_hysteresis.get_state();
 ├──> const bool maybe_landedDetected = _maybe_landed_hysteresis.get_state();
 ├──> const bool landDetected = _landed_hysteresis.get_state();
 ├──> const bool in_ground_effect = _ground_effect_hysteresis.get_state();
 │ 
 ├──> UpdateVehicleAtRest();
 │ 
 ├──> const bool at_rest = landDetected && _at_rest;
 │ 
 ├──> <(hrt_elapsed_time(&_land_detected.timestamp) >= 1_s) ||
 │       (_land_detected.landed != landDetected) ||
 │       (_land_detected.freefall != freefallDetected) ||
 │       (_land_detected.maybe_landed != maybe_landedDetected) ||
 │       (_land_detected.ground_contact != ground_contactDetected) ||
 │       (_land_detected.in_ground_effect != in_ground_effect) ||
 │       (_land_detected.at_rest != at_rest)>             // publish at 1 Hz, very first time, or when the result has changed
 │   ├──> <!landDetected && _land_detected.landed && _takeoff_time == 0> 
 │   │   └──> _takeoff_time = now_us// only set take off time once, until disarming
 │   ├──> _land_detected.landed = landDetected;
 │   ├──> _land_detected.freefall = freefallDetected;
 │   ├──> _land_detected.maybe_landed = maybe_landedDetected;
 │   ├──> _land_detected.ground_contact = ground_contactDetected;
 │   ├──> _land_detected.in_ground_effect = in_ground_effect;
 │   ├──> _land_detected.in_descend = 【可重载】_get_in_descend();
 │   ├──> _land_detected.has_low_throttle = 【可重载】_get_has_low_throttle();
 │   ├──> _land_detected.horizontal_movement = 【可重载】_get_horizontal_movement();
 │   ├──> _land_detected.vertical_movement = 【可重载】_get_vertical_movement();
 │   ├──> _land_detected.close_to_ground_or_skipped_check = 【可重载】_get_close_to_ground_or_skipped_check();
 │   ├──> _land_detected.at_rest = at_rest;
 │   ├──> _land_detected.timestamp = hrt_absolute_time();
 │   └──> _vehicle_land_detected_pub.publish(_land_detected);
 ├──> <_takeoff_time != 0 && !_armed && _previous_armed_state>
 │   ├──> _total_flight_time += now_us - _takeoff_time;
 │   ├──> _takeoff_time = 0;
 │   ├──> uint32_t flight_time = (_total_flight_time >> 32) & 0xffffffff;
 │   ├──> _param_total_flight_time_high.set(flight_time);
 │   ├──> _param_total_flight_time_high.commit_no_notification();
 │   ├──> flight_time = _total_flight_time & 0xffffffff;
 │   ├──> _param_total_flight_time_low.set(flight_time);
 │   └──> _param_total_flight_time_low.commit_no_notification();
 ├──> _previous_armed_state = _armed
 ├──> perf_end(_cycle_perf)
 └──> <should_exit()>
     ├──> ScheduleClear()
     └──> exit_and_cleanup()

注:这里用到了systemlib::Hysteresis类,有一定的迟滞作用。具体详见hysteresis.h/hysteresis.cpp

4. 总结

该模块最重要的任务就是更新发布vehicle_land_detected消息。

struct vehicle_land_detected_s {
	uint64_t timestamp;
	bool freefall;
	bool ground_contact;
	bool maybe_landed;
	bool landed;
	bool in_ground_effect;
	bool in_descend;
	bool has_low_throttle;
	bool vertical_movement;
	bool horizontal_movement;
	bool close_to_ground_or_skipped_check;
	bool at_rest;
	uint8_t _padding0[5]; // required for logger
}

鉴于不同机型判断逻辑不同,设计了统一的LandDetector业务监测框架,将具体判断逻辑放到LandDetector继承类的重载函数实现,详见3.1章节。

5. 参考资料

【1】PX4开源软件框架简明简介
【2】PX4模块设计之十一:Built-In框架
【3】PX4模块设计之十二:High Resolution Timer设计
【4】PX4模块设计之十三:WorkQueue设计
【5】PX4模块设计之十七:ModuleBase模块
【6】PX4 modules_main
【7】PX4模块设计之三十:Hysteresis类

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

PX4模块设计之二十七:LandDetector模块 的相关文章

  • PX4+QGC+jmavsim软件在环仿真

    一 环境修改 参考官方手册jMAVSim 仿真模拟 PX4 Developer Guide xff0c 以上环境基于上一篇内容 xff0c 未完成ROS 43 jmavsim 43 QGC环境搭建的请移步Ubuntu18 04下px4 43
  • 下载并构建PX4

    根据官方的文档 xff0c PX4下载和构建的方式有两种 xff1a Linux系列的Console模式 xff08 当然也支持Windows下的MINGW32 xff09 和Windows模式 在Windows平台下 xff0c 我们习惯
  • PX4二次开发中查无资料的踩坑总结

    写在前 xff1a 2021年9月下旬开始摸索px4飞控的二次开发 xff0c 从C 43 43 零基础到第一个修改算法后的版本稳定运行 xff0c 大概用了2个月 xff0c 从12月初改用新版本px4源码到现在又过去了约1个月 xff0
  • PX4 Offboard Control with MAVROS--Takeoff(一键起飞)

    警告 xff1a 请先在仿真环境下进行测试 xff0c 能达到预期效果后在进行实际飞行测试 xff0c 以免发生意外 本篇文章只是用作学习交流 xff0c 实际飞行时如出现意外情况作者不予以负责 所需材料 1 PIXhawk或者Pixrac
  • 飞行机器人(七)仿真平台XTDrone + PX4编译

    0 编译PX4固件 参考仿真平台基础配置教程 xff08 中文详细教程 xff09 仿真平台基础配置 语雀 yuque com https www yuque com xtdrone manual cn basic config 按照教程
  • 关于PX4中的高度若干问题

    飞行的高度是如何测量的 xff1f 地面的高度和海平面的高度差别很大 xff0c 飞控又是如何有效判别进行降落的 xff1f 这是我脑子里的疑问 搜索的一圈发现很少有人讨论这方面的问题 xff0c 于是本次我就直接看一下源代码 xff0c
  • Ubuntu20.04+MAVROS+PX4+Gazebo保姆级安装教程

    Ubuntu20 04 43 MAVROS 43 PX4 43 Gazebo 安装PX4步骤安装MAVROS安装QGCPX4仿真 安装PX4步骤 从github上clone源码 span class token function git s
  • PX4 Bootloader下载及编译过程中的问题解决

    买来的雷迅的板子都是Bootloader已经烧进去了 xff0c Fireware也已经刷进去了 如果是自制的板子 xff0c 上位机根本没法识别板子 xff0c 必须先烧写下载Bootloader后编译好的bin文件 这篇记一下自己下载及
  • px4 avoidance笔记

    最近在用px4官方的avoidance代码跑硬件避障 xff0c 官方介绍了只要生成符合sensor msgs PointCloud2点云信息就能使用 xff0c 因此为了应用长基线双目 xff0c 没有使用realsense的相机 xff
  • PX4飞控之PWM输出控制

    PX4飞控之PWM输出控制 多旋翼电调如好盈XRotor xff0c DJI通用电调等都支持PWM信号来传输控制信号 常用的400Hz电调信号对应周期2500us xff0c 一般使用高电平时间1000us 2000us为有效信号区间 xf
  • PX4进入系统控制台以及运行程序

    这里提供进入控制台两种办法 1 运行 Tools mavlink shell py dev ttyACM0 是我进入Px4系统控制台的命令 xff0c 进入之后应该是这样 Pixhawk src Firmware Tools mavlink
  • PX4 ---- Mixer

    文章目录 Mixer 混合控制 作用输入输出装载混控文件MAVROS代码解析总结示例MAINAUX Mixer 混合控制 作用 经过位置控制和姿态控制后 xff0c 控制量通过 actuator controls发布 xff0c 其中 co
  • PX4 ---- Indoor Flight

    文章目录 室内飞行ROS amp PX4Pose Data 飞机配置MAVROS 基于工训赛 VIO 飞行总结 室内飞行 ROS amp PX4 Pose Data 飞机配置 VIO 参考此处 xff0c 采用 T265 配置 相机与飞控机
  • PX4模块设计之五:自定义MAVLink消息

    PX4模块设计之五 xff1a 自定义MAVLink消息 1 MAVLink Dialects1 1 PX4 Dialects1 2 Paprazzi Dialects1 3 MAVLink XML File Format 2 添加自定义M
  • PX4模块设计之四十三:icm20689模块

    PX4模块设计之四十三 xff1a icm20689模块 1 icm20689模块简介2 模块入口函数2 1 主入口icm20689 main2 2 自定义子命令custom command2 3 模块状态print status 重载 3
  • px4_simple_example和uorb机制

    px4 simple app PX4 Autopilot src exampes px4 simple app xff0c 这个程序是用c语言调用orb API和poll机制订阅和发布通讯数据 xff0c 但是这个例子并不是既有接收又有发送
  • PX4-4-任务调度

    PX4所有的功能都封装在独立的模块中 xff0c uORB是任务间数据交互和同步的工具 xff0c 而管理和调度每个任务 xff0c PX4也提供了一套很好的机制 xff0c 这一篇我们分享PX4的任务调度机制 我们以PX4 1 11 3版
  • PX4飞控之自主返航(RTL)控制逻辑

    本文基于PX4飞控1 5 5版本 xff0c 分析导航模块中自护返航模式的控制逻辑和算法 自主返航模式和导航中的其他模式一样 xff0c 在Navigator main函数中一旦触发case vehicle status s NAVIGAT
  • 【PX4 飞控剖析】06 树莓派加载安装ROS,Mavros以及PX4固件

    PX4 飞控剖析 06 树莓派加载安装Mavros以及PX4固件 1 树莓派 刷镜像1 1 用Win32DiskImager刷入ubuntu mate 16 04 2 desktop armhf raspberry pi的镜像 1 2 开机
  • PX4项目学习::(七)飞控栈:commander

    PX4的飞行控制程序通过模块来实现 xff0c 与飞控相关的模块主要有commander xff0c navigator xff0c pos control xff0c att control这几个 xff0c 分别可以在src modul

随机推荐

  • 一文彻底搞懂为什么OpenCV用GPU/cuda跑得比用CPU慢?

    一 原因总结 最近项目需要 xff0c 发现了这个问题 网上找原因 xff0c 汇总起来 xff0c 有以下几点原因 xff1a 1 首先对于任何一个CUDA程序 xff0c 在调用它的第一个CUDA API时后都要花费秒级的时间去初始化运
  • solr学习二(ExtractingRequestHandler)

    size 61 large 通过ExtractingRequestHandler xff0c slor能够读取word pdf等文件 xff0c 并用于全文搜索 废话少说 xff0c 进入主题 xff1a color 61 darkred
  • 为什么函数参数const cv::Mat &img失效?仍旧可以修改const对象内容?

    1 举例如下 xff1a bool MainWindow readImage const QString amp path cv Mat img 61 cv imread path toStdString cv imwrite 34 d s
  • 我的Qt作品(18)模仿Qt Creator IDE写了一个轻量级的视觉框架

    Qt Creator的源码比较庞大 前几年我陆陆续续读过里面的源码 也写了几篇博文 xff1a https blog csdn net libaineu2004 article details 104728857 https blog cs
  • 关于turtlebot仿真报错The majority of dropped messages were due to..... 修改记录

    ros仿真过程中可能会出现类似错误 xff0c 雷达数据收不到 MessageFilter target 61 odom Dropped 100 00 of messages so far Please turn the ros gmapp
  • ESP32+WiFi+UART数据传输测试

    刚开始使用ESP32芯片 xff0c 摸索着实现了一个数据传输的功能 xff0c 记录下来以免忘记 实现功能 使用ESP32在服务器与下位机之间传输数据 xff0c 整体的流程图如下所示 如图所示 xff0c 下位机与ESP通过串口连接 x
  • ESP32+0.96寸OLED

    ESP32点亮0 96寸LED 考虑在上一篇的写那个项目中添加一个屏幕的显示 xff0c OLED屏幕为淘宝购买的6针型号蓝绿双色的屏幕 xff0c 通过四线SPI与ESP32连接 OLED屏电路图 OLED实物图 这是连接好运行后的图 x
  • ESP32+485(MODBUS RTU)

    1 背景 需要采集功率表的功率及电量数据 xff0c 考虑采用ESP32采集数据后发送给服务器 所需硬件 xff1a ESP32开发板 485从机 232转485芯片 图1 连接示意图 2 实现 数字功率表采用Modbus RTU模式进行数
  • Qt5.12.11交叉编译+64位ARM_aarch64+全志H5 CortexA53

    1 准备工作 购买的H5开发板 xff0c 附带资料里面只有关于qt4 8的支持 xff0c Qt5新增了很多插件 xff0c 为了在H5上运行Qt5的程序 xff0c 需要交叉编译Qt5版本的源码 xff0c 记录下编译Qt5 12 11
  • ESP32接入百度云,在线语音识别

    1开发环境及工具 开发板使用的是ESP32 LyraTv4 3 入下图所示 xff0c 开环境在是在Ubuntu20 04上搭建的ESP IDF xff0c 在ESP IDF中添加了支持语音开发的sdk xff0c ESP ADF 2开发过
  • ARM 7 三级 中断流水线

    ARM 7 在冯诺依曼 结构的 是三级流水线技术 分别是 取址 译码 执行 当有BL 的指令 执行时 流水线 也会被阻断 在分支指令执行的时候 其后第一条指令 被 解码 第二条 指令 被 取址 xff0c 当前的PC指针是 指在取址这的 x
  • S5PC100 I2C总线

    I2C 使用2根双向信号线来传递数据 SCL 时钟线 SDA 数据线 特点 半双功 xff0c 仅需要2根线 一般在PCU 上占2个PIN I2C 总线 上 都是 oc od 输出 xff0c 所以使用上拉电阻 当总线空闲的时候 都是输出
  • java代码自动生成一(freemarker)

    size 61 large 网上有很多代码自动生成工具 xff0c 如abator和hibernate xff0c 这些工具虽好 xff0c 却没有源码 xff0c 不能修改模板 xff0c 让人很不爽 我刚毕业的时候 xff0c 项目经理
  • linux内核 2.6.35下的驱动例子

    创建 设备节点 mknod dev hello c 字符设备 或者b xff08 块设备 xff09 250 1 查看 cat proc devices 当前设备节点 insmod 安装 rmmod 删除 编译 Makefile 1 需要配
  • E:Could not get lock /var/lib/apt/lists/lock - open (11: Resource temporarily unavailable)

    出现这个问题的原因可能是有另外一个程序正在运行 xff0c 导致资源被锁不可用 而导致资源被锁的原因 xff0c 可能是上次安装时没正常完成 xff0c 而导致出现此状况 解决方法 xff1a 输入以下命令 sudo rm var cach
  • shell 脚本中的引用问题

    原始代码如下 bin sh myvar 61 34 Hello world 34 echo myvar echo 34 myvar 34 echo 39 myvar 39 echo myvar echo Enter some test re
  • Linux内核的TCP源码入门(一)

    文章目录 前言一 TCP报文段结构1 报文段整体结构2 TCP首部 固定部分3 TCP首部 选项 options 二 TCP接收和发送数据1 TCP的 34 接口 34 2 发送数据3 接收数据3 1 ip层向上调用INET Socket层
  • 【API接口工具】postman-Windows版、Linux安装

    Windows安装 Postman 适用于 Windows 7 及更高版本 下载最新的 Postman 版本 选择并运行该 exe文件以安装 Postman Postman v9 4 是 Postman 的最后一个版本 xff0c 同时支持
  • 四轴飞控DIY调试起飞简明步骤

    四轴飞控DIY调试起飞简明步骤 调试起飞简明步骤Step1 xff1a 飞控配置Step2 xff1a 试飞目标测试内容坐标系 Step3 xff1a 试飞方法1 升降 xff08 Throttle xff09 2 偏航 xff08 yaw
  • PX4模块设计之二十七:LandDetector模块

    PX4模块设计之二十七 xff1a LandDetector模块 1 LandDetector模块简介2 模块入口函数2 1 主入口land detector main2 2 自定义子命令custom command 3 LandDetec