3.5RC_Channel 和 SRV_channel

2023-05-16

前言

 这部分是之前在折腾ROVER的时候梳理了一遍,但是没有形成记录,现在从新从对象的角度来分析一遍,包括映射、转换、数据结构...等方面进行梳理;

数据结构

 首先分析的入口是从Rover::read_radio()的函数进行,我们就从这里为入口并作为本次分析的主线来进行阐述:
void Rover::read_radio()
{
//1如果没有新的RC信号,执行失控保护
  if (!hal.rcin->new_input()) {
  control_failsafe(channel_throttle->get_radio_in());
  return;
  }

  failsafe.last_valid_rc_ms = AP_HAL::millis();

  //获取所有RC通道,并根据初始设定的方式[angle/range]按设置范围归一化保存至control_in中
  RC_Channels::set_pwm_all();

  control_failsafe(channel_throttle->get_radio_in());

  //2处理伺服辅助功能
  SRV_Channels::set_output_scaled(SRV_Channel::k_throttle,channel_throttle->get_control_in());

  // Check if the throttle value is above 50% and we need to nudge
  // Make sure its above 50% in the direction we are travelling
  ....
  ...
  ..

  //3开启舵机平滑
  if (g.skid_steer_in) {
  // convert the two radio_in values from skid steering values

  float motor1 = channel_steer->norm_input();
  float motor2 = channel_throttle->norm_input();
  float steering_scaled = motor1 - motor2;
  float throttle_scaled = 0.5f*(motor1 + motor2);
  int16_t steer = channel_steer->get_radio_trim();
  int16_t thr = channel_throttle->get_radio_trim();
  channel_steer->set_pwm(steer);
  channel_throttle->set_pwm(thr);
  ....
  ...
  ..

  //4舵机解锁检测
  rudder_arm_disarm_check();
}

这里涉及到的几个对象单独罗列出来进行分析:
RC_Channel
RC_Channels
SRV_Channel
SRV_Channels

RC_Channels

 首先是RC_Channels,从下面的定义来看内部定义了很多静态函数,并定义了定义了一组RC_Channel的数组以及指针,RC_Channels::set_pwm_all(void)的主要作用直接读取hal.rcin的值按range/angle转换并保存至control_in中;这里先不深入研究。
/*
  class RC_Channels. Hold the full set of RC_Channel objects
*/
class RC_Channels {
public:
  friend class SRV_Channels;                          #申明SRV_Channels是其友元类
  // constructor
  RC_Channels(void);                                  #构造函数,并对channels[i].ch_in赋值通道号

  static const struct AP_Param::GroupInfo var_info[];

  static RC_Channel *rc_channel(uint8_t chan) {      #返回RC_Channles[chan]指针
  return (chan < NUM_RC_CHANNELS)?&channels[chan]:nullptr;
  }

  static void set_pwm_all(void);

private:
  // this static arrangement is to avoid static pointers in AP_Param tables
  static RC_Channel *channels;                       #指向obj_channels[NUM_RC_CHANNELS]的首地址
  RC_Channel obj_channels[NUM_RC_CHANNELS];
};

总的来说RC_Channels就是一个定义了RC_Channel数组长度[16]且具备操作所有通道的输出的类;

RC_Channel

 接下来就是RC_Channel,主要是抽象出了单个通道的数据结构,下面先从成员变量进行分析;
/// @class RC_Channel
/// @brief Object managing one RC channel
class RC_Channel {
public:
  friend class SRV_Channels;
  friend class RC_Channels;
  // Constructor
  RC_Channel(void);

  // used to get min/max/trim limit value based on _reverse
  enum LimitValue {
  RC_CHANNEL_LIMIT_TRIM,
  RC_CHANNEL_LIMIT_MIN,
  RC_CHANNEL_LIMIT_MAX
  };

  // startup
  void load_eeprom(void);
  void save_eeprom(void);
  void save_trim(void);

  // setup the control preferences,设置获取通道数值范围/反相/死区的方法
  void set_range(uint16_t high);
  void set_angle(uint16_t angle);
  bool get_reverse(void) const;
  void set_default_dead_zone(int16_t dzone);
  uint16_t get_dead_zone(void) const { return dead_zone; }

  // get the center stick position expressed as a control_in value
  int16_t get_control_mid() const;

  // read input from hal.rcin - create a control_in value
  void set_pwm(int16_t pwm);
  void set_pwm_no_deadzone(int16_t pwm);

  // calculate an angle given dead_zone and trim. This is used by the quadplane code
  // for hover throttle
  int16_t pwm_to_angle_dz_trim(uint16_t dead_zone, uint16_t trim);

  /*
  return a normalised input for a channel, in range -1 to 1,
  centered around the channel trim. Ignore deadzone.
  归一化通道的数值为[-1,1]
  */
  float norm_input();

  /*
  return a normalised input for a channel, in range -1 to 1,
  centered around the channel trim. Take into account the deadzone
  归一化通道的数值为[-1,1],增加死区
  */
  float norm_input_dz();

  uint8_t percent_input();
  int16_t pwm_to_range();
  int16_t pwm_to_range_dz(uint16_t dead_zone);

  // read the input value from hal.rcin for this channel,从硬件抽象层中获取RC信号
  uint16_t read() const;

  // read input from hal.rcin and set as pwm input for channel
  void input();

  static const struct AP_Param::GroupInfo var_info[];

  // return true if input is within deadzone of trim
  bool in_trim_dz();

  int16_t get_radio_in() const { return radio_in;}
  void set_radio_in(int16_t val) {radio_in = val;}

  int16_t get_control_in() const { return control_in;}
  void set_control_in(int16_t val) { control_in = val;}

  // get control input with zero deadzone
  int16_t get_control_in_zero_dz(void);

  int16_t get_radio_min() const {return radio_min.get();}
  void set_radio_min(int16_t val) { radio_min = val;}

  int16_t get_radio_max() const {return radio_max.get();}
  void set_radio_max(int16_t val) {radio_max = val;}

  int16_t get_radio_trim() const { return radio_trim.get();}
  void set_radio_trim(int16_t val) { radio_trim.set(val);}
  void save_radio_trim() { radio_trim.save();}

  bool min_max_configured() const
  {
  return radio_min.configured() && radio_max.configured();
  }

private:

  // pwm is stored here
  // RC通道读出的原始值的保存位置
  int16_t radio_in;

  // value generated from PWM normalised to configured scale
  // RC通道原始值经过归一化和配置后的保存位置
  int16_t control_in;

  AP_Int16 radio_min;     #RC通道原始值的最小值
  AP_Int16 radio_trim;    #RC通道原始值的中位值
  AP_Int16 radio_max;     #RC通道原始值的最大值

  AP_Int8 reversed;       #RC通道反相标志
  AP_Int16 dead_zone;     #RC通道死区

  uint8_t type_in;        #RC输入值类型是角度还是范围
  int16_t high_in;

  // the input channel this corresponds to
  uint8_t ch_in;          #RC通道号

  int16_t pwm_to_angle();
  int16_t pwm_to_angle_dz(uint16_t dead_zone);
};
 所有从上面的数据结构就可以看出,RC_Channel抽象的RC通道如上面注释所描述,其成员函数主要是围绕变量的设置...

在初始的通道号分配时,还涉及到RCMapper rcmap,这个主要是通道映射,在其构造函数中,通过const AP_Param::GroupInfo RCMapper::var_info[]对其成员变量进行赋值,根本上还是对通道进行映射;

RCMapper

class RCMapper
{
public:
  /// Constructor
  ///
  RCMapper();

  /// roll - return input channel number for roll / aileron input
  uint8_t roll() const { return _ch_roll; }

  /// pitch - return input channel number for pitch / elevator input
  uint8_t pitch() const { return _ch_pitch; }

  /// throttle - return input channel number for throttle input
  uint8_t throttle() const { return _ch_throttle; }

  /// yaw - return input channel number for yaw / rudder input
  uint8_t yaw() const { return _ch_yaw; }

  /// forward - return input channel number for forward input
  uint8_t forward() const { return _ch_forward; }

  /// lateral - return input channel number for lateral input
  uint8_t lateral() const { return _ch_lateral; }

  static const struct AP_Param::GroupInfo var_info[];

private:
  // channel mappings
  AP_Int8 _ch_roll;
  AP_Int8 _ch_pitch;
  AP_Int8 _ch_yaw;
  AP_Int8 _ch_throttle;
  AP_Int8 _ch_forward;
  AP_Int8 _ch_lateral;
};
const AP_Param::GroupInfo RCMapper::var_info[] = {
  // @Param: ROLL
  // @DisplayName: Roll channel
  // @Description: Roll channel number.
  // @Range: 1 8
  // @Increment: 1
  // @User: Advanced
  // @RebootRequired: True
  AP_GROUPINFO("ROLL", 0, RCMapper, _ch_roll, 1),
  AP_GROUPINFO("PITCH", 1, RCMapper, _ch_pitch, 2),
  AP_GROUPINFO("THROTTLE", 2, RCMapper, _ch_throttle, 3),
  AP_GROUPINFO("YAW", 3, RCMapper, _ch_yaw, 4),
  AP_GROUPINFO_FRAME("FORWARD", 4, RCMapper, _ch_forward, 6, AP_PARAM_FRAME_SUB),
  AP_GROUPINFO_FRAME("LATERAL", 5, RCMapper, _ch_lateral, 7, AP_PARAM_FRAME_SUB),
};

最终在使用的时候:
1.只需要定义一个RC_Channel的指针;
2.然后通过RC_Channels::rc_channel()返回一个实际通道指针;
3.实际通道指针的映射存在于RCMapper::var_info[];
关于使用上面三点了解了也就基本能使用了,接下来深入一点就是这个PWM的值究竟是怎么来的,从RC_Channel类中不难发现:

void
RC_Channel::input()
{
  radio_in = hal.rcin->read(ch_in);
}

uint16_t
RC_Channel::read() const
{
  return hal.rcin->read(ch_in);
}
 上述两个方法的中调用都涉及到了hal.rcin,从RCInput可以找到相关实现,最终可以找到是通过orb_copy(ORB_ID(input_rc), _rc_sub, &_rcin);来获取的到外部输入的RC 信号的;
void PX4RCInput::_timer_tick(void)
{
  perf_begin(_perf_rcin);
  bool rc_updated = false;
  if (orb_check(_rc_sub, &rc_updated) == 0 && rc_updated) {
  pthread_mutex_lock(&rcin_mutex);
  orb_copy(ORB_ID(input_rc), _rc_sub, &_rcin);
  pthread_mutex_unlock(&rcin_mutex);
  }
  // note, we rely on the vehicle code checking new_input()
  // and a timeout for the last valid input to handle failsafe
  perf_end(_perf_rcin);
}
 通过全局搜索我们可以在PX4Firmware/src/driver/px4_fmu/fmu.cpp中找到下面的函数,传输的_rc_in则是通过void

PX4FMU::fill_rc_in()来进行填充的,也就是我们拿到的原始包含pwm的值;

void
PX4FMU::cycle_trampoline(void *arg)
{
PX4FMU *dev = reinterpret_cast<PX4FMU *>(arg);

dev->cycle();
}

而cycle中就有通过UORB发布input_rc的话题,同时调用了work_queue进行循环,仔细一看就会发现这个函数里面还有对安全开关的操作;

// slave safety from IO
...
..
/* check arming state */
...
..

if (rc_updated) {
/* lazily advertise on first publication */
if (_to_input_rc == nullptr) {
     _to_input_rc = orb_advertise(ORB_ID(input_rc), &_rc_in);

} else {
     orb_publish(ORB_ID(input_rc), _to_input_rc, &_rc_in);
}
}

work_queue(HPWORK, &_work, (worker_t)&PX4FMU::cycle_trampoline, this,
USEC2TICK(SCHEDULE_INTERVAL - main_out_latency));
到这里基本上能明白的是px4_fmu也是公共继承了CDev的类和之前的I2C、SPI一样都是属于字符型驱动;相同情况px4_io也是同样的是公共继承了CDev的字符类驱动;从nsh的终端上“ls dev”也可以看出,px对fmu和io的抽象,按照官网说明那样fmu和io之间是通过串口进行通信的,而在fmu的work_queue中还没有发现相关源码。这里需要在整理;

SRV_Channel

 SRV_Channel是对输出通道的抽象出的数据结构,枚举了所有PWM通道;实现了单个SRV_Channel的从信号的输入到输出的计算,并且附加了对通道数值的类型和限幅操作;
/*
  class SRV_Channel. The class SRV_Channels contains an array of
  SRV_Channel objects. This is done to fit within the AP_Param limit
  of 64 parameters per object.
*/
class SRV_Channel {
public:
  friend class SRV_Channels;
  // constructor
  SRV_Channel(void);

  static const struct AP_Param::GroupInfo var_info[];

  typedef enum
  {
  k_none = 0, ///< disabled
  k_manual = 1, ///< manual, just pass-thru the RC in signal
  k_flap = 2, ///< flap
  k_flap_auto = 3, ///< flap automated
  k_aileron = 4, ///< aileron
  k_unused1 = 5, ///< unused function
  k_mount_pan = 6, ///< mount yaw (pan)
  k_mount_tilt = 7, ///< mount pitch (tilt)
  k_mount_roll = 8, ///< mount roll
  k_mount_open = 9, ///< mount open (deploy) / close (retract)
  k_cam_trigger = 10, ///< camera trigger
  k_egg_drop = 11, ///< egg drop
  k_mount2_pan = 12, ///< mount2 yaw (pan)
  k_mount2_tilt = 13, ///< mount2 pitch (tilt)
  k_mount2_roll = 14, ///< mount2 roll
  k_mount2_open = 15, ///< mount2 open (deploy) / close (retract)
  k_dspoiler1 = 16, ///< differential spoiler 1 (left wing)
  k_dspoiler2 = 17, ///< differential spoiler 2 (right wing)
  k_aileron_with_input = 18, ///< aileron, with rc input
  k_elevator = 19, ///< elevator
  k_elevator_with_input = 20, ///< elevator, with rc input
  k_rudder = 21, ///< secondary rudder channel
  k_sprayer_pump = 22, ///< crop sprayer pump channel
  k_sprayer_spinner = 23, ///< crop sprayer spinner channel
  k_flaperon1 = 24, ///< flaperon, left wing
  k_flaperon2 = 25, ///< flaperon, right wing
  k_steering = 26, ///< ground steering, used to separate from rudder
  k_parachute_release = 27, ///< parachute release
  k_gripper = 28, ///< gripper
  k_landing_gear_control = 29, ///< landing gear controller
  k_engine_run_enable = 30, ///< engine kill switch, used for gas airplanes and helicopters
  k_heli_rsc = 31, ///< helicopter RSC output
  k_heli_tail_rsc = 32, ///< helicopter tail RSC output
  k_motor1 = 33, ///< these allow remapping of copter motors
  k_motor2 = 34,
  k_motor3 = 35,
  k_motor4 = 36,
  k_motor5 = 37,
  k_motor6 = 38,
  k_motor7 = 39,
  k_motor8 = 40,
  k_motor_tilt = 41, ///< tiltrotor motor tilt control
  k_rcin1 = 51, ///< these are for pass-thru from arbitrary rc inputs
  k_rcin2 = 52,
  k_rcin3 = 53,
  k_rcin4 = 54,
  k_rcin5 = 55,
  k_rcin6 = 56,
  k_rcin7 = 57,
  k_rcin8 = 58,
  k_rcin9 = 59,
  k_rcin10 = 60,
  k_rcin11 = 61,
  k_rcin12 = 62,
  k_rcin13 = 63,
  k_rcin14 = 64,
  k_rcin15 = 65,
  k_rcin16 = 66,
  k_ignition = 67,
  k_choke = 68,
  k_starter = 69,
  k_throttle = 70,
  k_tracker_yaw = 71, ///< antennatracker yaw
  k_tracker_pitch = 72, ///< antennatracker pitch
  k_throttleLeft = 73,
  k_throttleRight = 74,
  k_nr_aux_servo_functions ///< This must be the last enum value (only add new values _before_ this one)
  } Aux_servo_function_t;

  // used to get min/max/trim limit value based on reverse
  enum LimitValue {
  SRV_CHANNEL_LIMIT_TRIM,
  SRV_CHANNEL_LIMIT_MIN,
  SRV_CHANNEL_LIMIT_MAX,
  SRV_CHANNEL_LIMIT_ZERO_PWM
  };

  // set the output value as a pwm value 设置当前通道的待输出的PWM值
  void set_output_pwm(uint16_t pwm);

  // get the output value as a pwm value 获取当前通道输出的PWM值
  uint16_t get_output_pwm(void) const { return output_pwm; }

  // set angular range of scaled output 设置在转换为PWM信号时,最大输入角度
  void set_angle(int16_t angle);

  // set range of scaled output. Low is always zero 设置在转换为PWM信号时,最大输入范围
  void set_range(uint16_t high);

  // return true if the channel is reversed 返回通道是否反相
  bool get_reversed(void) const {
  return reversed?true:false;
  }

  // set MIN/MAX parameters  设置通道的PWM最大最小值
  void set_output_min(uint16_t pwm) {
  servo_min.set(pwm);
  }
  void set_output_max(uint16_t pwm) {
  servo_max.set(pwm);
  }

  // get MIN/MAX/TRIM parameters 获取通道的PWM最大最小值
  uint16_t get_output_min(void) const {
  return servo_min;
  }
  uint16_t get_output_max(void) const {
  return servo_max;
  }
  uint16_t get_trim(void) const {
  return servo_trim;
  }

private:
  AP_Int16 servo_min;
  AP_Int16 servo_max;
  AP_Int16 servo_trim;
  // reversal, following convention that 1 means reversed, 0 means normal
  AP_Int8 reversed;
  AP_Int8 function;

  // a pending output value as PWM
  uint16_t output_pwm;

  // true for angle output type
  bool type_angle:1;

  // set_range() or set_angle() has been called
  bool type_setup:1;

  // the hal channel number
  uint8_t ch_num;

  // high point of angle or range output
  uint16_t high_out;

  // convert a 0..range_max to a pwm 将PWM转换为范围
  uint16_t pwm_from_range(int16_t scaled_value) const;

  // convert a -angle_max..angle_max to a pwm 将PWM转换为角度
  uint16_t pwm_from_angle(int16_t scaled_value) const;

  // convert a scaled output to a pwm value 输入output_scaled[范围、角度]转换为PWM并set_output_pwm();
  void calc_pwm(int16_t output_scaled);

  // output value based on function, 调用hal.rcout直接输出PWM
  void output_ch(void);

  // setup output type and range based on function
  void aux_servo_function_setup(void);

  // return PWM for a given limit value
  uint16_t get_limit_pwm(LimitValue limit) const;

  // get normalised output from -1 to 1
  float get_output_norm(void);

  // a bitmask type wide enough for NUM_SERVO_CHANNELS
  typedef uint16_t servo_mask_t;

  // mask of channels where we have a output_pwm value. Cleared when a
  // scaled value is written.
  static servo_mask_t have_pwm_mask;
};

SRV_Channels

 与SRV_Channel互为友元类,在成员变量上定义了SRV_Channels的类数组,方法上更对是对SRV_Channel的补充,例如设置中位、设置失控保护值....

下面分析一个简单的例子:

首先指定通道function(类中枚举的值)和待写入的value,这个值会被保存在functions[function].output_scaled中;
void SRV_Channels::set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value);
 |
 V
SCHED_TASK(set_servos, 50, 1500),//全部PWM输出这里会周期执行,里面会计算来自RC信号/其他填充的信号
 |
 V
先调用SRV_Channels::calc_pwm();
再执行SRV_Channels::output_ch_all();
 |
 V
channels[i].output_ch();//最终回归到SRV_Channel 定义的channels[i]数组
 |
 V
hal.rcout->write(ch_num, output_pwm);//调用AP_HAL执行输出;
/// map a function to a servo channel and output it
void SRV_Channel::output_ch(void)
{
  int8_t passthrough_from = -1;

  // take care of special function cases,根据通道的编号进行不同处理,1,[51,66]k_rcin1~k_rcin16均为直通信号
  switch(function)
  {
  case k_manual: // manual
    passthrough_from = ch_num;
  break;
  case k_rcin1 ... k_rcin16: // rc pass-thru,转换后的通道编号为0~15
    passthrough_from = int8_t(function - k_rcin1);
  break;
  case k_motor1 ... k_motor8:
    // handled by AP_Motors::rc_write()
  return;
  }
  if (passthrough_from != -1) {
  // we are doing passthrough from input to output for this channel
  RC_Channel *rc = RC_Channels::rc_channel(passthrough_from);
  if (rc) {
  if (SRV_Channels::passthrough_disabled()) {
       output_pwm = rc->get_radio_trim();
  } else {
       output_pwm = rc->get_radio_in();
  }
  }
  }
  hal.rcout->write(ch_num, output_pwm);//直接通过抽象层输出,这里继续往下就要看回AP_HAL_PX下的RCOutput.cpp
}

总结

RC_Channel、RC_Channels、SRV_Channel、SRV_Channels这4个类都是基于hal.rcin和hal.rcout与硬件沟通的;

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

3.5RC_Channel 和 SRV_channel 的相关文章

  • 【Java】【NIO】【01】NIO设计理念

    什么是NIO NIO中的N 既有New的含义 也有Non blocking的含义 它是Java1 4之后推出来的一套非阻塞式IO接口 用于解决高并发 提升IO性能 NIO的主要改变 NIO主要的改变在于以下几点 通过Channel取代Str
  • Netty入门-Channel

    目录 Channel详解 Channel的特点 Channel接口方法 ChannelOutboundInvoker接口 AttributeMap接口 ChannelHandler接口 ChannelInboundHandler接口 Cha
  • SRV 记录的 Java DNS 查找

    在下面的 java 代码中 我进行 DNS SRV 记录查找 以解析给定域名 例如 root 1000000000 blubluzone com 的目标域名和关联端口 用 表示的查找函数HERE 下面以某种方式返回 null 我无法获得查询
  • 解决 goroutine 死锁

    我一直在尝试解决我在Golang并发中遇到的这个简单问题 我一直在搜索所有可能的解决方案 但没有发现任何特定于我的问题的解决方案 或者我可能会错过一个 这是我的代码 package main import fmt time func pro
  • 有没有办法让 Go 的通道表现得像堆栈

    据我所知 默认情况下 Go 通道的行为类似于队列 先进先出 有什么办法可以将它们更改为后进先出吗 基本上 我正在进行搜索 并希望出于内存限制而使用 DFS 而不是 BFS 不 这是不可能的 通道始终是 FIFO 你可以使用包containe
  • 如何对线程使用静态生命周期?

    我目前正在为 Rust 1 0 的生命周期而苦苦挣扎 尤其是在通过通道传递结构时 我如何编译这个简单的例子 use std sync mpsc Receiver Sender use std sync mpsc use std thread
  • 如何通过 telethon 获取 telegram 私人频道 id

    您好 不知道如何解决这个问题 因此我们将非常感谢任何帮助 我订阅了私人频道 该频道没有用户名 我也没有邀请链接 管理员刚刚添加了我 由于我在工作中使用此频道 为了加快处理速度 我想使用 Telethon 处理在该频道上发布的消息 该方案的核
  • 在golang中将chan转换为non chan

    是否可以让函数funcWithNonChanResult有如下接口 func funcWithNonChanResult int 如果我想让它使用函数funcWithChanResult与接口 func funcWithChanResult
  • Django Websockets 数据发送到错误的套接字

    使用 Django Websockets Channels 我创建了一个 一个 组 并且来回消息工作得很好 我们称之为A组 当我在不同的浏览器中打开第二个组和第二个 我们称之为 B 组 WebSocket 连接时 问题就开始了 我尝试发送到
  • 在docker容器中运行djangoworker和daphne

    我有在 docker 容器中运行的 django 应用程序 最近我发现我需要向我的应用程序添加 websockets 接口 我在 nginx 和 redis 后面使用带有 daphne 的通道作为缓存 问题是我必须在 1 个容器中运行 dj
  • WCF 最大消息大小配额

    我正在尝试调用 WCF 服务 托管在 Windows 服务中 而不是 IIS 但收到以下错误 最大消息大小配额 传入消息已超出 对于远程通道 请参阅 服务器日志以获取更多详细信息 我尝试将 MaxReceivedMessageSize 和
  • django 通道 websocket 连接不工作

    我正在尝试从服务器上的 django Channels examples 运行多聊天项目 它可以在 Windows 计算机上本地运行 但是当我将其放在 Linux 服务器上并使用 runserver 启动它时 它不会 manage py r
  • Google App Engine 中通道池的最佳方法

    似乎使 GAE Channel API 在财务上可行的唯一方法是实施某种池化机制 当我向他们发送有关过高价格的电子邮件时 一位高级应用程序引擎产品经理甚至告诉我这一点 以重用尚未使用的渠道已到期 我一直在集思广益地讨论实现通道池的方法 地点
  • 是否可以将多个通道复用为一个通道?

    这个想法是在切片中拥有可变数量的通道 将通过它们接收到的每个值推送到单个通道中 并在最后一个输入通道关闭后关闭该输出通道 类似这样 但对于两个以上的通道数 func multiplex cin1 cin2 cout chan int n 2
  • 通过 Django Channels 和 Websockets 将实时更新推送到客户端

    我正在尝试制作一个向客户端显示实时更新数据的页面 该网站的其余部分是使用 Django 构建的 因此我尝试使用 Channels 来实现此目的 我显示的数据保存在 JSON 文件和 MySQL 数据库中 以便在网站的其他部分进行进一步计算
  • 将channel_priority设置为“strict”是否会影响所有Conda环境?

    我使用 R 创建了一个 Conda 环境the 康达锻造公司频道说明 https conda forge org docs user introduction html how can i install packages from con
  • Golang:我可以投射到 chan 接口吗{}

    我正在尝试为订阅编写一个通用包装器 例如 type Subscriber interface Subscribe addr string chan interface 假设有一个我想使用的库 其中有一个 subscribe 方法 但它使用c
  • Python 3:如何更改GDAL中的图像数据?

    我有一个 GeoTIFF 图像 其中包含颜色表和带有 8 位表键的单个栅格带 并且使用 LZW 压缩 我加载该图像gdal Open https gdal org python osgeo gdal module html 我还有一个包含
  • 如何计算位图的平均 RGB 颜色值

    在我的 C 3 5 应用程序中 我需要获取位图的红色 绿色和蓝色通道的平均颜色值 最好不使用外部库 这可以做到吗 如果是这样 怎么办 提前致谢 尝试让事情变得更精确 位图中的每个像素都有一定的 RGB 颜色值 我想获取图像中所有像素的平均
  • Django Channels/Daphne 内部服务器错误“‘dict’对象不可调用”

    我在连接到我的网站时收到此错误 因为它正在运行频道 2018 03 25 20 59 19 049 ERROR http protocol Traceback most recent call last File home virtuale

随机推荐

  • LoRa和NB-IoT有什么区别?LoRa的优势在哪些方面?

    对于LoRa技术 xff0c 行业内人士都不会陌生 xff0c 它也经常会被拿来和NB IoT技术比较 作为低功耗广域网 xff08 LPWAN xff09 的新兴技术 xff0c 两种技术都备受关注 对于LoRa技术 xff0c 行业内人
  • Source Insight 4.0最好看的主题

    推荐一款sourceinsight主题 xff0c 4 0适用 xff0c 配色本人觉得非常舒服 使用方法 xff1a 1 安装Sourceinsight 2 安装字体 xff1a YaHei Consolas Hybrid 1 12 tt
  • Notepad++最好看的主题

    Notepad 43 43 最好看的主题 xff0c 收藏了很久 xff0c 现在拿出来和大家分享 配色如下 xff1a 使用方法 xff1a 1 安装Notepad 43 43 2 将KamiTheme xml放到 Notepad 43
  • DTLS协议中client/server的认证过程和密钥协商过程

    1 DTLS介绍 1 1 DTLS的作用 互联网先驱们最开始在设计互联网协议时主要考虑的是可用性 xff0c 安全性是没有考虑在其中的 xff0c 所以传输层的TCP UDP协议本身都不具备安全性 SSL TLS协议是基于TCP socke
  • Ubuntu18.04 实现串口通信

    最近由于项目需要 xff0c 研究了关于在ubuntu下串口通信的功能实现 期间遇到一些问题 xff0c 跟大家分享下 1 代码 comm service h ifndef comm service h define comm servic
  • [STM32] 串口数据帧处理(第一弹)

    文章目录 1 串口使用的常用场景2 字节帧处理总结 1 串口使用的常用场景 使用串口的主要目的是实现数据的交互 xff0c 数据的交互的方法脱身于常用的场景 这里描述一个比较典型的场景 xff1a MCU作为主控制器通过串口和外部的设备或者
  • 串口编程—(1)串口基本知识

    串口是用来干什么的 xff1f 串行接口 简称串口 xff0c 也称 串行通信 接口或 串行通讯接口 xff08 通常指 COM接口 xff09 xff0c 是采用 串行通信 方式的扩展接口 串行接口 Serial Interface 是指
  • C语言操作redis数据库

    文章目录 1 开发环境2 C语言redis库 hiredi安装配置2 1 下载并且解压hiredis2 2 hiredis安装 3 hiredis简单测试4 运行出错解决办法5 验证5 1 运行程序5 2 redis客户端验证 1 开发环境
  • 5.0 NuttX File System

    转载请注明出处 xff1a 5 0 NuttX File System Alvin Peng的博客 CSDN博客 文章均出自个人理解 前言 前一段时间折腾了几个驱动 xff08 PWM Serial I2C xff09 xff0c 这次来折
  • 使用cmake构建一个大型项目框架

    文章目录 使用CMake构建一个大型项目工程1 大型工程目录结构介绍1 1 工程目录结构介绍1 2 工程目录说明 xff08 我是这样设计的 xff0c 你们也可以参考类似这样设计 xff09 1 3 最外层CMakeLists txt说明
  • github下载加速的几种方法

    文章目录 1 github加速的几种办法1 1 把github的代码 xff0c 转到码云上1 2 有人做了github的代下载网站 xff0c 可以从上面进行下载1 3 使用cnpmjs镜像进行加速1 4 使用国外服务器进行搭桥 2 总结
  • EasyLogger的代码解读和移植(linux和stm)

    文章目录 1 EasyLogger目录结构分析 2 EasyLogger之docs查看总结 2 1 EasyLogger之docs查看 2 1 2 api gt kernel md文档 2 1 3 port gt kernel md文档 2
  • C++之socket.io编译使用

    文章目录 1 什么是socket io2 开发环境配置2 1 获取socket io的源码2 2 cmake安装2 3 boost安装2 3 1 获取源码2 3 2 解压编译下载 2 4 rapidjson下载2 5 websocketpp
  • github push的改版

    1 记录一次github 推送时的错误 错误如下 xff1a remote Please see https github blog 2020 12 15 token authentication requirements for git
  • Frp内网穿透

    Frp内网穿透 所有经过服务器的内网穿透都是有一个服务端和客户端 因为都需要借助服务器的公网ip来访问进而达到内网穿透的效果 frp的github开源地址 https github com fatedier frp frp的说明文档 htt
  • linux常见的几种排序方法

    我们以数组a 61 2 6 8 9 1 2 进行排序输出作为列子 xff1a 下面我来总结几种方法来帮助大家学习 1 xff1a 常规排序 首先2和6对比 xff0c 2不比6大不因此不交换 xff0c 所以还是268912 xff0c 然
  • 值得推荐的C/C++框架和库

    值得学习的C语言开源项目 Libevent libev是一个开源的事件驱动库 xff0c 基于epoll xff0c kqueue等OS提供的基础设施 其以高效出名 xff0c 它可以将IO事件 xff0c 定时器 xff0c 和信号统一起
  • cmake教程4(find_package使用)

    本文主要内容如下 xff1a 1 cmake find package的基本原理 2 如何编写自己的 cmake module模块 3 使用cmake find package 使用不同版本的opencv lib问题 xff08 openc
  • A*算法

    如此好贴 xff0c 不能不转 xff01 原文地址 xff1a http dev gameres com Program Abstract Arithmetic AmitAStar mht 本文版权归原作者 译者所有 xff0c 我只是转
  • 3.5RC_Channel 和 SRV_channel

    前言 这部分是之前在折腾ROVER的时候梳理了一遍 xff0c 但是没有形成记录 xff0c 现在从新从对象的角度来分析一遍 xff0c 包括映射 转换 数据结构 等方面进行梳理 xff1b 数据结构 首先分析的入口是从Rover read