ArduPilot飞控启动&运行过程简介

这篇具有很好参考价值的文章主要介绍了ArduPilot飞控启动&运行过程简介。希望对大家有所帮助。如果存在错误或未考虑完全的地方,请大家不吝赐教,您也可以点击"举报违法"按钮提交疑问。

1. 源由

ArduPilot从整体的设计框架角度,感觉是更加容易上手,尤其是对一些相对熟悉C语言/嵌入式固件开发的兄弟们来说。

  1. 基于Ardunio编程方式
  2. 采用C++类方式进行抽象
  3. 应用业务模块化
  4. 模块考虑重复利用
  5. 设备代码工程隔离
  6. ArduPilot自研任务调度

注:飞控由于其历史发展以及时间同步因素,大量的使用了自研的任务调度,这个和常见的OS任务调度有很大的差异,请大家特别注意。

为了更好从一个整体来理解ArduPilot代码行为,我们直接从启动&运行过程入手,围绕这根主线,类似鱼骨图方式展开研读和学习。

2. Copter飞控

鉴于官网文档也指出,从设计文档的角度来说,Copter相对详细(尽快也已经很久没有更新了)。因此,我们就重点关注Copter的启动&运行过程。

2.1 入口

ArduCopter/Copter.cpp

AP_HAL_MAIN_CALLBACKS(&copter);

libraries/AP_HAL/AP_HAL_Main.h

#ifndef AP_MAIN
#define AP_MAIN main
#endif

#define AP_HAL_MAIN() \
    AP_HAL::HAL::FunCallbacks callbacks(setup, loop); \
    extern "C" {                               \
    int AP_MAIN(int argc, char* const argv[]); \
    int AP_MAIN(int argc, char* const argv[]) { \
        hal.run(argc, argv, &callbacks); \
        return 0; \
    } \
    }

#define AP_HAL_MAIN_CALLBACKS(CALLBACKS) extern "C" { \
    int AP_MAIN(int argc, char* const argv[]); \
    int AP_MAIN(int argc, char* const argv[]) { \
        hal.run(argc, argv, CALLBACKS); \
        return 0; \
    } \
    }

2.2 启动(run)

根据Copter硬件配置情况,可能使用不同的OS操作系统。

通常情况来说,硬件采用ChibiOS嵌入式操作系统。

libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp

void HAL_ChibiOS::run(int argc, char * const argv[], Callbacks* callbacks) const
 ├──> <HAL_USE_SERIAL_USB == TRUE> usb_initialise()
 ├──> <HAL_STDOUT_SERIAL> sdStart((SerialDriver*)&HAL_STDOUT_SERIAL, &stdoutcfg)  //STDOUT Initialisation
 ├──> g_callbacks = callbacks
 └──> main_loop()  //Takeover main

这里的callbacks=&copter,而Copter对象继承自AP_Vehicle。所以可以知道g_callbacks里面所带的setup/loop是AP_Vehicle::setup/AP_Vehicle::loop。

ArduCopter/Copter.h

class Copter : public AP_Vehicle {

2.3 运行(main_loop)

libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp

static void main_loop()
 ├──> daemon_task = chThdGetSelfX();
 ├──> chThdSetPriority(APM_MAIN_PRIORITY);  //switch to high priority for main loop
 ├──> <HAL_I2C_CLEAR_BUS> ChibiOS::I2CBus::clear_all();
 ├──> <AP_HAL_SHARED_DMA_ENABLED> ChibiOS::Shared_DMA::init();
 ├──> peripheral_power_enable();
 ├──> <HAL_SPI_CHECK_CLOCK_FREQ> ChibiOS::SPIDevice::test_clock_freq();
 ├──> hal.analogin->init();

 ##################################################
 # hal.scheduler                                  #
 ##################################################
 ├──> hal.scheduler->init();
 
 ├──> hal_chibios_set_priority(APM_STARTUP_PRIORITY);
 ├──> <stm32_was_watchdog_reset()> 
 │   ├──> stm32_watchdog_load((uint32_t *)&utilInstance.persistent_data, (sizeof(utilInstance.persistent_data)+3)/4);
 │   └──> utilInstance.last_persistent_data = utilInstance.persistent_data;
 ├──> schedulerInstance.hal_initialized();
 
 ##################################################
 # AP_Vehicle::setup                              #
 ##################################################
 
 ├──> g_callbacks->setup();
 ├──> <HAL_ENABLE_SAVE_PERSISTENT_PARAMS> utilInstance.apply_persistent_params();
 ├──> <HAL_FLASH_PROTECTION> 
 │   ├──> <AP_BoardConfig::unlock_flash()> stm32_flash_unprotect_flash();
 │   └──> <else> stm32_flash_protect_flash(false, AP_BoardConfig::protect_flash()); stm32_flash_protect_flash(true, AP_BoardConfig::protect_bootloader());
 ├──> <!defined(DISABLE_WATCHDOG)>
 │   ├──> <IOMCU_FW> stm32_watchdog_init();
 │   └──> <!IOMCU_FW>
 │       ├──> <AP_BoardConfig::watchdog_enabled()> stm32_watchdog_init();
 │       └──> <hal.util->was_watchdog_reset()> INTERNAL_ERROR(AP_InternalError::error_t::watchdog_reset);
 ├──> schedulerInstance.watchdog_pat();
 ├──> hal.scheduler->set_system_initialized();
 ├──> thread_running = true;
 ├──> chRegSetThreadName(SKETCHNAME);
 ├──> chThdSetPriority(APM_MAIN_PRIORITY); //switch to high priority for main loop
 ├──> <while (true)>
 
 ##################################################
 # AP_Vehicle::loop                               #
 ##################################################
 
 │   ├──> g_callbacks->loop();
 │   ├──> <!defined(HAL_DISABLE_LOOP_DELAY) && !APM_BUILD_TYPE(APM_BUILD_Replay)> <!schedulerInstance.check_called_boost()> hal.scheduler->delay_microseconds(50);
 │   └──> schedulerInstance.watchdog_pat();
 └──> thread_running = false;

3. Ardunio编程

因为基于Ardunio编程方式,所以在启动&运行过程中,先调用setup进行初始化设备,在主线程中进行loop运行。

3.1 setup - AP_Vehicle::setup

libraries/AP_Vehicle/AP_Vehicle.cpp

void AP_Vehicle::setup()
 ├──> AP_Param::setup_sketch_defaults(); // load the default values of variables listed in var_info[]
 ├──> serial_manager.init_console();  // initialise serial port
 ├──> DEV_PRINTF("\n\nInit %s"
 │                      "\n\nFree RAM: %u\n",
 │                      AP::fwversion().fw_string,
 │                      (unsigned)hal.util->available_memory());
 ├──> <AP_CHECK_FIRMWARE_ENABLED> check_firmware_print();
 ├──> AP_Param::check_var_info(); // validate the static parameter table,
 ├──> load_parameters();  // then load persistentvalues from storage:
 ├──> <CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS> <AP_BoardConfig::get_sdcard_slowdown() != 0> // user wants the SDcard slower, we need to remount
 │   ├──> sdcard_stop();
 │   └──> sdcard_retry();
 ├──> get_scheduler_tasks(tasks, task_count, log_bit);
 ├──> AP::scheduler().init(tasks, task_count, log_bit);
 ├──> G_Dt = scheduler.get_loop_period_s();  // time per loop - this gets updated in the main loop() based on actual loop rate
 
 ##################################################
 # this is here for Plane; its failsafe_check method requires the
 # RC channels to be set as early as possible for maximum
 # survivability.
 ##################################################
 
 ├──> set_control_channels();

 ##################################################
 # initialise serial manager as early as sensible to get
 # diagnostic output during boot process.  We have to initialise
 # the GCS singleton first as it sets the global mavlink system ID
 # which may get used very early on.
 ##################################################

 ├──> gcs().init();

 ##################################################
 # initialise serial ports                        #
 ##################################################
 
 ├──> serial_manager.init();
 ├──> gcs().setup_console();

 ##################################################
 # Register scheduler_delay_cb, which will run anytime you have
 # more than 5ms remaining in your call to hal.scheduler->delay
 ##################################################
 
 ├──> hal.scheduler->register_delay_callback(scheduler_delay_callback, 5);

 ├──> <HAL_MSP_ENABLED> msp.init(); // call MSP init before init_ardupilot to allow for MSP sensors
 ├──> <HAL_EXTERNAL_AHRS_ENABLED> externalAHRS.init(); // call externalAHRS init before init_ardupilot to allow for external sensors
 ├──> init_ardupilot();  // init_ardupilot is where the vehicle does most of its initialisation.
 ├──> <AP_AIRSPEED_ENABLED>
 │   ├──> airspeed.init();
 │   ├──> <airspeed.enabled()>
 │   │   └──> airspeed.calibrate(true);
 │   └──> <APM_BUILD_TYPE(APM_BUILD_ArduPlane)> GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"No airspeed sensor present or enabled");
 ├──> <!APM_BUILD_TYPE(APM_BUILD_Replay)> SRV_Channels::init(); 
 ├──> <HAL_GYROFFT_ENABLED>  // gyro FFT needs to be initialized really late
 │   └──> gyro_fft.init(AP::scheduler().get_loop_rate_hz());
 ├──> <HAL_RUNCAM_ENABLED> runcam.init();
 ├──> <HAL_HOTT_TELEM_ENABLED> hott_telem.init();
 ├──> <HAL_VISUALODOM_ENABLED> visual_odom.init();  // init library used for visual position estimation
 ├──> <AP_VIDEOTX_ENABLED> vtx.init();
 ├──> <AP_SMARTAUDIO_ENABLED> smartaudio.init();
 ├──> <AP_TRAMP_ENABLED> tramp.init();
 ├──> <AP_PARAM_KEY_DUMP> AP_Param::show_all(hal.console, true);
 ├──> send_watchdog_reset_statustext();
 ├──> <HAL_GENERATOR_ENABLED> generator.init();
 ├──> <AP_OPENDRONEID_ENABLED> opendroneid.init();
 ├──> <HAL_EFI_ENABLED> efi.init(); // init EFI monitoring
 ├──> <AP_TEMPERATURE_SENSOR_ENABLED> temperature_sensor.init();
 ├──> <AP_AIS_ENABLED> ais.init();
 ├──> <HAL_NMEA_OUTPUT_ENABLED> nmea.init();
 ├──> <AP_FENCE_ENABLED> fence.init();
 ├──> <custom_rotations.init();
 ├──> <HAL_WITH_ESC_TELEM && HAL_GYROFFT_ENABLED>
 │   └──> for (uint8_t i = 0; i<ESC_TELEM_MAX_ESCS; i++) {
 │       └──> esc_noise[i].set_cutoff_frequency(2);
 ├──> AP_Param::invalidate_count(); // invalidate count in case an enable parameter changed during initialisation
 └──> gcs().send_text(MAV_SEVERITY_INFO, "ArduPilot Ready");

3.2 loop - AP_Vehicle::loop

libraries/AP_Vehicle/AP_Vehicle.cpp

void AP_Vehicle::loop()
 ├──> scheduler.loop();
 ├──> G_Dt = scheduler.get_loop_period_s();
 ├──> <!done_safety_init>
 │   │  /*
 │   │    disable safety if requested. This is delayed till after the
 │   │    first loop has run to ensure that all servos have received
 │   │    an update for their initial values. Otherwise we may end up
 │   │    briefly driving a servo to a position out of the configured
 │   │    range which could damage hardware
 │   │  */
 │   ├──> done_safety_init = true;
 │   ├──> BoardConfig.init_safety();
 │   ├──> char banner_msg[50];
 │   └──> <hal.rcout->get_output_mode_banner(banner_msg, sizeof(banner_msg))> GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", banner_msg); // send RC output mode info if available
 ├──> const uint32_t new_internal_errors = AP::internalerror().errors();
 └──> _last_internal_errors != new_internal_errors>
     ├──> AP::logger().Write_Error(LogErrorSubsystem::INTERNAL_ERROR, LogErrorCode::INTERNAL_ERRORS_DETECTED);
     ├──> gcs().send_text(MAV_SEVERITY_CRITICAL, "Internal Errors 0x%x", (unsigned)new_internal_errors);
     └──> _last_internal_errors = new_internal_errors;

4. ArduCopter任务

ArduCopter任务的调用栈逻辑依次是:

AP_Vehicle::loop
 └──> scheduler.loop
     └──> run
         └──> task.function

task.function是ArduCopter/Copter.cpp中给出的任务列表对应的函数。这张表格给出了ArduCopter所有的任务。飞控运行时,将不断的通过表中任务的优先级进行切换运行。

注:关于每个任务的执行细节方面,我们后续抽时间将会逐一研究,也请大家持续关注,谢谢!

/*
  scheduler table - all tasks should be listed here.

  All entries in this table must be ordered by priority.

  This table is interleaved with the table in AP_Vehicle to determine
  the order in which tasks are run.  Convenience methods SCHED_TASK
  and SCHED_TASK_CLASS are provided to build entries in this structure:

SCHED_TASK arguments:
 - name of static function to call
 - rate (in Hertz) at which the function should be called
 - expected time (in MicroSeconds) that the function should take to run
 - priority (0 through 255, lower number meaning higher priority)

SCHED_TASK_CLASS arguments:
 - class name of method to be called
 - instance on which to call the method
 - method to call on that instance
 - rate (in Hertz) at which the method should be called
 - expected time (in MicroSeconds) that the method should take to run
 - priority (0 through 255, lower number meaning higher priority)

 */
const AP_Scheduler::Task Copter::scheduler_tasks[] = {
    // update INS immediately to get current gyro data populated
    FAST_TASK_CLASS(AP_InertialSensor, &copter.ins, update),
    // run low level rate controllers that only require IMU data
    FAST_TASK(run_rate_controller),
#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED
    FAST_TASK(run_custom_controller),
#endif
#if FRAME_CONFIG == HELI_FRAME
    FAST_TASK(heli_update_autorotation),
#endif //HELI_FRAME
    // send outputs to the motors library immediately
    FAST_TASK(motors_output),
     // run EKF state estimator (expensive)
    FAST_TASK(read_AHRS),
#if FRAME_CONFIG == HELI_FRAME
    FAST_TASK(update_heli_control_dynamics),
#endif //HELI_FRAME
    // Inertial Nav
    FAST_TASK(read_inertia),
    // check if ekf has reset target heading or position
    FAST_TASK(check_ekf_reset),
    // run the attitude controllers
    FAST_TASK(update_flight_mode),
    // update home from EKF if necessary
    FAST_TASK(update_home_from_EKF),
    // check if we've landed or crashed
    FAST_TASK(update_land_and_crash_detectors),
    // surface tracking update
    FAST_TASK(update_rangefinder_terrain_offset),
#if HAL_MOUNT_ENABLED
    // camera mount's fast update
    FAST_TASK_CLASS(AP_Mount, &copter.camera_mount, update_fast),
#endif
    FAST_TASK(Log_Video_Stabilisation),

    SCHED_TASK(rc_loop,              250,    130,  3),
    SCHED_TASK(throttle_loop,         50,     75,  6),
    SCHED_TASK_CLASS(AP_GPS,               &copter.gps,                 update,          50, 200,   9),
#if AP_OPTICALFLOW_ENABLED
    SCHED_TASK_CLASS(AP_OpticalFlow,          &copter.optflow,             update,         200, 160,  12),
#endif
    SCHED_TASK(update_batt_compass,   10,    120, 15),
    SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&copter.g2.rc_channels, read_aux_all,    10,  50,  18),
    SCHED_TASK(arm_motors_check,      10,     50, 21),
#if TOY_MODE_ENABLED == ENABLED
    SCHED_TASK_CLASS(ToyMode,              &copter.g2.toy_mode,         update,          10,  50,  24),
#endif
    SCHED_TASK(auto_disarm_check,     10,     50,  27),
    SCHED_TASK(auto_trim,             10,     75,  30),
#if RANGEFINDER_ENABLED == ENABLED
    SCHED_TASK(read_rangefinder,      20,    100,  33),
#endif
#if HAL_PROXIMITY_ENABLED
    SCHED_TASK_CLASS(AP_Proximity,         &copter.g2.proximity,        update,         200,  50,  36),
#endif
#if BEACON_ENABLED == ENABLED
    SCHED_TASK_CLASS(AP_Beacon,            &copter.g2.beacon,           update,         400,  50,  39),
#endif
    SCHED_TASK(update_altitude,       10,    100,  42),
    SCHED_TASK(run_nav_updates,       50,    100,  45),
    SCHED_TASK(update_throttle_hover,100,     90,  48),
#if MODE_SMARTRTL_ENABLED == ENABLED
    SCHED_TASK_CLASS(ModeSmartRTL,         &copter.mode_smartrtl,       save_position,    3, 100,  51),
#endif
#if HAL_SPRAYER_ENABLED
    SCHED_TASK_CLASS(AC_Sprayer,           &copter.sprayer,               update,         3,  90,  54),
#endif
    SCHED_TASK(three_hz_loop,          3,     75, 57),
    SCHED_TASK_CLASS(AP_ServoRelayEvents,  &copter.ServoRelayEvents,      update_events, 50,  75,  60),
    SCHED_TASK_CLASS(AP_Baro,              &copter.barometer,             accumulate,    50,  90,  63),
#if PRECISION_LANDING == ENABLED
    SCHED_TASK(update_precland,      400,     50,  69),
#endif
#if FRAME_CONFIG == HELI_FRAME
    SCHED_TASK(check_dynamic_flight,  50,     75,  72),
#endif
#if LOGGING_ENABLED == ENABLED
    SCHED_TASK(loop_rate_logging, LOOP_RATE,    50,  75),
#endif
    SCHED_TASK_CLASS(AP_Notify,            &copter.notify,              update,          50,  90,  78),
    SCHED_TASK(one_hz_loop,            1,    100,  81),
    SCHED_TASK(ekf_check,             10,     75,  84),
    SCHED_TASK(check_vibration,       10,     50,  87),
    SCHED_TASK(gpsglitch_check,       10,     50,  90),
    SCHED_TASK(takeoff_check,         50,     50,  91),
#if AP_LANDINGGEAR_ENABLED
    SCHED_TASK(landinggear_update,    10,     75,  93),
#endif
    SCHED_TASK(standby_update,        100,    75,  96),
    SCHED_TASK(lost_vehicle_check,    10,     50,  99),
    SCHED_TASK_CLASS(GCS,                  (GCS*)&copter._gcs,          update_receive, 400, 180, 102),
    SCHED_TASK_CLASS(GCS,                  (GCS*)&copter._gcs,          update_send,    400, 550, 105),
#if HAL_MOUNT_ENABLED
    SCHED_TASK_CLASS(AP_Mount,             &copter.camera_mount,        update,          50,  75, 108),
#endif
#if AP_CAMERA_ENABLED
    SCHED_TASK_CLASS(AP_Camera,            &copter.camera,              update,          50,  75, 111),
#endif
#if LOGGING_ENABLED == ENABLED
    SCHED_TASK(ten_hz_logging_loop,   10,    350, 114),
    SCHED_TASK(twentyfive_hz_logging, 25,    110, 117),
    SCHED_TASK_CLASS(AP_Logger,            &copter.logger,              periodic_tasks, 400, 300, 120),
#endif
    SCHED_TASK_CLASS(AP_InertialSensor,    &copter.ins,                 periodic,       400,  50, 123),

    SCHED_TASK_CLASS(AP_Scheduler,         &copter.scheduler,           update_logging, 0.1,  75, 126),
#if AP_RPM_ENABLED
    SCHED_TASK_CLASS(AP_RPM,               &copter.rpm_sensor,          update,          40, 200, 129),
#endif
    SCHED_TASK_CLASS(AP_TempCalibration,   &copter.g2.temp_calibration, update,          10, 100, 135),
#if HAL_ADSB_ENABLED
    SCHED_TASK(avoidance_adsb_update, 10,    100, 138),
#endif
#if ADVANCED_FAILSAFE == ENABLED
    SCHED_TASK(afs_fs_check,          10,    100, 141),
#endif
#if AP_TERRAIN_AVAILABLE
    SCHED_TASK(terrain_update,        10,    100, 144),
#endif
#if AP_GRIPPER_ENABLED
    SCHED_TASK_CLASS(AP_Gripper,           &copter.g2.gripper,          update,          10,  75, 147),
#endif
#if AP_WINCH_ENABLED
    SCHED_TASK_CLASS(AP_Winch,             &copter.g2.winch,            update,          50,  50, 150),
#endif
#ifdef USERHOOK_FASTLOOP
    SCHED_TASK(userhook_FastLoop,    100,     75, 153),
#endif
#ifdef USERHOOK_50HZLOOP
    SCHED_TASK(userhook_50Hz,         50,     75, 156),
#endif
#ifdef USERHOOK_MEDIUMLOOP
    SCHED_TASK(userhook_MediumLoop,   10,     75, 159),
#endif
#ifdef USERHOOK_SLOWLOOP
    SCHED_TASK(userhook_SlowLoop,      3.3,   75, 162),
#endif
#ifdef USERHOOK_SUPERSLOWLOOP
    SCHED_TASK(userhook_SuperSlowLoop, 1,     75, 165),
#endif
#if HAL_BUTTON_ENABLED
    SCHED_TASK_CLASS(AP_Button,            &copter.button,              update,           5, 100, 168),
#endif
#if STATS_ENABLED == ENABLED
    SCHED_TASK_CLASS(AP_Stats,             &copter.g2.stats,            update,           1, 100, 171),
#endif
};

5. 参考资料

【1】ArduPilot开源飞控系统之简单介绍
【2】ArduPilot之开源代码框架
【3】ArduPilot飞控之ubuntu22.04-SITL安装
【4】ArduPilot飞控之ubuntu22.04-Gazebo模拟
【5】ArduPilot飞控之Mission Planner模拟
【6】ArduPilot飞控AOCODARC-H7DUAL固件编译
【7】ArduPilot之开源代码Library&Sketches设计
【8】ArduPilot之开源代码Sensor Drivers设计
【9】ArduPilot之开源代码基础知识&Threading概念
【10】ArduPilot之开源代码UARTs and the Console使用文章来源地址https://www.toymoban.com/news/detail-720612.html

到了这里,关于ArduPilot飞控启动&运行过程简介的文章就介绍完了。如果您还想了解更多内容,请在右上角搜索TOY模板网以前的文章或继续浏览下面的相关文章,希望大家以后多多支持TOY模板网!

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处: 如若内容造成侵权/违法违规/事实不符,请点击违法举报进行投诉反馈,一经查实,立即删除!

领支付宝红包 赞助服务器费用

相关文章

  • 无人机/飞控--ArduPilot、PX4学习记录(5)

    这几天看dronekit,做无人机失控保护。 PX4官网上的经典案例,我做了很多注解,把代码过了一遍。 无人机具体执行了:  先起飞,飞至正上空10m-向北移动10m-向东移动10m-向南移动10m-向西移动10m-回到初始起飞点(即home点),降落。 具体执行之前,要打开JMAVSim,接下来会在JMAV

    2024年04月15日
    浏览(40)
  • ardupilot开发 --- ardupilot parameter与mavlink massage篇

    除了可以再初始化设置外,ardupilot parameters一般通过mavlink massage来动态设置; https://ardupilot.org/copter/docs/parameters.html https://mavlink.io/en/messages/common.html https://blog.csdn.net/weixin_43321489/article/details/132236353

    2024年02月10日
    浏览(36)
  • ardupilot开发 --- git 篇

    工作区:就是你在电脑里能看到的目录; 暂存区:stage区 或 index区。存放在 :工作区 / .git / index 文件中; 版本库:本地仓库,存放在 :工作区 / .git 中 关于 HEAD 是所有本地分支的游标(指针); HEAD既可以指向某个分支,还可以指向某个分支的某个(次)提交; HEAD指向谁,

    2024年02月04日
    浏览(36)
  • ardupilot开发 --- 深度相机 篇

    需要机载计算机作为中介!!

    2024年02月06日
    浏览(34)
  • Ardupilot环境搭建

    Ardpilot介绍:ArduPilot通过多种传感器的数据(GPS、加速度计、气压计、磁场计)等来估计飞行器的姿态,从而使飞行器能够保持稳定。被称为APM的飞控硬件,其实全程就是Ardu Pilot Mega,但是2013年后,这个系列的飞控硬件改名为Pixhawk,ArduPilot只用来指特定的飞控软件,但是约定

    2024年02月07日
    浏览(28)
  • Ardupilot学习笔记

    https://doc.cuav.net/tutorial/copter 【1】https://ardupilot.org 一套开源的自驾仪,集成了各种各样的代码,包括其他开源代码(如PX4代码)和项目、驱动等。 即:自驾仪即集成了整个可以实现无人载具(如无人机)自动驾驶功能的代码。 指定硬件(即target board)后,将Ardupilot编译后的可以

    2024年02月12日
    浏览(35)
  • ardupilot开发 --- Lua脚本篇

    ArduPilot引入了对Lua脚本的支持; 可以同时运行多个脚本; Lua脚本存放在 SD card 中; Copter-4.0 及以上版本才支持Lua脚本; scripting API ?scripting applets ? 飞控条件:2 MB of flash and 70 kB of memory ; 将Lua脚本上传到 SD card’s APM/scripts 文件夹中,在Mission Planner使用MAVFTP可以上传文件;

    2024年02月11日
    浏览(30)
  • ardupilot 遥控的输入控制模式

    本节主要记录自己整理ardupilot的遥控器的输入控制模式:正常模式、简单模式、超简单模式的理解。 在不用简单和超简单的模式的情况下,无人机操作员操作的控制输入是对应着不断旋转着的飞行器进行操作的。如上方图所示举例,当无人机操作员进行向右(红色)的 横滚

    2024年02月15日
    浏览(31)
  • ubuntu下ardupilot编译环境搭建与仿真

    虽然怒飞老师给出了详细的windows下的开发环境的搭建教程。但是对于开发者而言,最好的系统环境还是在Linux系统下,尤其一些顶层开发下,还是用ROS香呀,所以我将尝试在ubuntu下建立完整的ardupilot开发环境。这篇文章就作为这个尝试的第一篇笔记,希望可以帮助到之后的朋

    2023年04月23日
    浏览(22)
  • (4)(4.6.1) ArduPilot操作的简单概述

    文章目录 前言 1 基本目标 2 输入 3 输出 4 传感器 5 参数说明 这是一个非常基本的 ArduPilot 固件运行在 自动驾驶仪 上的功能概述。下面显示的是一个基本功能操作的简单框图。这将使你在配置系统时对 ArduPilot 的基本功能有一个更好的了解。 软件的基本目标是提供对飞行器的

    2024年02月08日
    浏览(32)

觉得文章有用就打赏一下文章作者

支付宝扫一扫打赏

博客赞助

微信扫一扫打赏

请作者喝杯咖啡吧~博客赞助

支付宝扫一扫领取红包,优惠每天领

二维码1

领取红包

二维码2

领红包