APM-RGB颜色控制-通过飞行指令控制

本文不涉及统一APM飞控和QGC的MAVLINK库
因为目前搞不来
APM飞控修改

  1. 定义并声明一组全局变量
    libraries/AP_Mission/navcmdtoled.h
extern int rgb_r233;
extern int rgb_g233;
extern int rgb_b233;

libraries/AP_Mission/navcmdtoled.cpp

#include </libraries/AP_Mission/navcmdtoled.h>
int rgb_r233=127;
int rgb_g233=127;
int rgb_b233=127;
  1. 注释case MAV_CMD_NAV_DELAY:
    libraries/AP_Mission/AP_Mission.cpp
 for (uint8_t i=0; i<16; i++, cmd_index++) {
        if (!get_next_nav_cmd(cmd_index, cmd)) {
            return false;
        }
        switch (cmd.id) {
        // any of these are considered a takeoff command:
        case MAV_CMD_NAV_TAKEOFF:
        case MAV_CMD_NAV_TAKEOFF_LOCAL:
            return true;
        // any of these are considered "skippable" when determining if
        // we "start with a takeoff command"
       // case MAV_CMD_NAV_DELAY:
            continue;
        default:
            return false;
        }
    }
  1. ArduCopter/mode_auto.cpp
#include </libraries/AP_Mission/navcmdtoled.h>
void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd)
{
           rgb_r233=(cmd.content.nav_delay.hour_utc*6);
           rgb_g233=(cmd.content.nav_delay.min_utc*6);
           rgb_b233=(cmd.content.nav_delay.sec_utc*6);
    nav_delay_time_start_ms = millis();

    if (cmd.content.nav_delay.seconds > 0) {
        // relative delay
        nav_delay_time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds
    // } else {
    //     // absolute delay to utc time
    //     nav_delay_time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0);
    // }
    }
    gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000));
}
  1. libraries/AP_Notify/RGBLed.cpp
#include </libraries/AP_Mission/navcmdtoled.h>
set_rgb(rgb_r233,rgb_g233,rgb_b233);

QGC修改

  1. D:\qgroundcontrol\src\MissionManager\MavCmdInfoCommon.json
        {
            "id":           93,
            "rawName":      "MAV_CMD_NAV_DELAY",
            "friendlyName": "LED-Delay until",
            "description":  "LED-Delay unti the specified time is reached.",
            "category":     "Basic",
            "param1": {
                "label":            "Hold",
                "units":            "secs",
                "default":          0,
                "decimalPlaces":    0
            },
            "param2": {
                "label":            "R-Hour (utc)",
                "units":            "0-21",
                "default":          0,
                "decimalPlaces":    0
            },
            "param3": {
                "label":            "G-Min (utc)",
                "units":            "0-21",
                "default":          0,
                "decimalPlaces":    0
            },
            "param4": {
                "label":            "B-Sec (utc)",
                "units":            "0-21",
                "default":          0,
                "decimalPlaces":    0
            }
        },
  1. D:\qgroundcontrol\src\FirmwarePlugin\APM\APMFirmwarePlugin.cc
QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
{
    return {
        MAV_CMD_NAV_WAYPOINT_LED,
        MAV_CMD_NAV_WAYPOINT,
        MAV_CMD_NAV_LOITER_UNLIM, MAV_CMD_NAV_LOITER_TURNS, MAV_CMD_NAV_LOITER_TIME,
        MAV_CMD_NAV_RETURN_TO_LAUNCH, MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
        MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT,
        MAV_CMD_NAV_LOITER_TO_ALT,
        MAV_CMD_NAV_SPLINE_WAYPOINT,
        MAV_CMD_NAV_GUIDED_ENABLE,
        MAV_CMD_NAV_DELAY,
        MAV_CMD_CONDITION_DELAY, MAV_CMD_CONDITION_DISTANCE, MAV_CMD_CONDITION_YAW,
        MAV_CMD_DO_SET_MODE,
        MAV_CMD_DO_JUMP,
        MAV_CMD_DO_CHANGE_SPEED,
        MAV_CMD_DO_SET_HOME,
        MAV_CMD_DO_SET_RELAY, MAV_CMD_DO_REPEAT_RELAY,
        MAV_CMD_DO_SET_SERVO, MAV_CMD_DO_REPEAT_SERVO,
        MAV_CMD_DO_LAND_START,
        MAV_CMD_DO_SET_ROI,
        MAV_CMD_DO_DIGICAM_CONFIGURE, MAV_CMD_DO_DIGICAM_CONTROL,
        MAV_CMD_DO_MOUNT_CONTROL,
        MAV_CMD_DO_SET_CAM_TRIGG_DIST,
        MAV_CMD_DO_FENCE_ENABLE,
        MAV_CMD_DO_PARACHUTE,
        MAV_CMD_DO_INVERTED_FLIGHT,
        MAV_CMD_DO_GRIPPER,
        MAV_CMD_DO_GUIDED_LIMITS,
        MAV_CMD_DO_AUTOTUNE_ENABLE,
        MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND, MAV_CMD_DO_VTOL_TRANSITION,
#if 0
    // Waiting for module update
        MAV_CMD_DO_SET_REVERSE,
#endif
    };
}
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值