diff --git a/chip/basic/basic_h/stm32_header.h b/chip/basic/basic_h/stm32_header.h index 086dd2f..c8acdf9 100644 --- a/chip/basic/basic_h/stm32_header.h +++ b/chip/basic/basic_h/stm32_header.h @@ -40,6 +40,7 @@ #ifdef HAL_HASH_MODULE_ENABLED #endif #ifdef HAL_I2C_MODULE_ENABLED +#include "i2c.h" #endif #ifdef HAL_I2S_MODULE_ENABLED #endif diff --git a/chip/zgpio.hpp b/chip/zgpio.hpp index 866ceba..a4ff0db 100644 --- a/chip/zgpio.hpp +++ b/chip/zgpio.hpp @@ -33,6 +33,20 @@ class ZGPIO { typedef function onirq_t; + typedef struct { + Pin_t pin; + GPIOMode_t mode; + GPIOIrqType_t irqtype; + bool mirror; + } InputGpioCfg_t; + + typedef struct { + Pin_t pin; + GPIOMode_t mode; + bool mirror; + bool initLevel; + } OutputGpioCfg_t; + private: GPIO_TypeDef *m_gpio; uint16_t m_pinoff; diff --git a/chip/zpwm_generator_muti_channel.cpp b/chip/zpwm_generator_muti_channel.cpp new file mode 100644 index 0000000..56b9eab --- /dev/null +++ b/chip/zpwm_generator_muti_channel.cpp @@ -0,0 +1,84 @@ +#include "zpwm_generator_muti_channel.hpp" + +#include "zirq_dispatcher.hpp" +using namespace iflytop; + +void ZPWMGeneratorMutiChannel::initialize(zchip_tim_t *htim, float freq, bool polarity) { + m_htim = htim; + m_polarity = polarity; + m_freq = freq; + + ZEARLY_ASSERT(m_htim->Init.AutoReloadPreload == TIM_AUTORELOAD_PRELOAD_ENABLE); + ZEARLY_ASSERT(m_htim->Init.CounterMode == TIM_COUNTERMODE_UP); + + /** + * @brief 初始化频率 + */ + uint32_t prescaler = 0; + uint32_t autoreload = 0; + + uint32_t timClkFreq = chip_get_timer_clock_sorce_freq(m_htim); + ZEARLY_ASSERT(chip_calculate_prescaler_and_autoreload_by_expect_freq(timClkFreq, m_freq, &prescaler, &autoreload)); + __HAL_TIM_SET_AUTORELOAD(m_htim, autoreload); + __HAL_TIM_SET_PRESCALER(m_htim, prescaler); +} + +/****************************************************** + * kTimMode_timer * + ******************************************************/ + +bool ZPWMGeneratorMutiChannel::isPWMStart(int32_t channelindex) { + if (channelindex < 1 || channelindex > 4) return false; + return m_pwmstate[channelindex]; +} +void ZPWMGeneratorMutiChannel::updatePWMState(int32_t channelindex /*1,2,3,4*/, float duty) { + if (!m_polarity) { + duty = 100.0 - duty; + } + + uint32_t channel = 0; + if (channelindex == 1) { + channel = TIM_CHANNEL_1; + } else if (channelindex == 2) { + channel = TIM_CHANNEL_2; + } else if (channelindex == 3) { + channel = TIM_CHANNEL_3; + } else if (channelindex == 4) { + channel = TIM_CHANNEL_4; + } + + /** + * @brief + */ + TIM_OC_InitTypeDef sConfigOC = {0}; + sConfigOC.OCMode = TIM_OCMODE_PWM1; + sConfigOC.Pulse = duty / 100.0 * __HAL_TIM_GET_AUTORELOAD(m_htim); + sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; + sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; + sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET; + sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET; + + if (HAL_TIM_PWM_ConfigChannel(m_htim, &sConfigOC, channel) != HAL_OK) { + Error_Handler(); + } + HAL_TIM_PWM_Stop(m_htim, channel); + if (HAL_TIM_PWM_Start(m_htim, channel) != HAL_OK) { + Error_Handler(); + } +} + +void ZPWMGeneratorMutiChannel::startPWM(int32_t channelindex /*1,2,3,4*/, float duty) { + if (channelindex < 1 || channelindex > 4) return; + m_pwmstate[channelindex] = true; + updatePWMState(channelindex, duty); +} +void ZPWMGeneratorMutiChannel::stopPWM(int32_t channelindex) { + if (channelindex < 1 || channelindex > 4) return; + m_pwmstate[channelindex] = false; + float duty = 0; + if (!m_polarity) { + duty = 100.0 - duty; + } + // HAL_TIM_PWM_Stop(m_htim, m_channel); + startPWM(channelindex, duty); +} diff --git a/chip/zpwm_generator_muti_channel.hpp b/chip/zpwm_generator_muti_channel.hpp new file mode 100644 index 0000000..c5cdfea --- /dev/null +++ b/chip/zpwm_generator_muti_channel.hpp @@ -0,0 +1,46 @@ + +#pragma once +#include + +#include "basic/base.hpp" + +#ifdef HAL_TIM_MODULE_ENABLED + +namespace iflytop { +using namespace iflytop; + +class ZPWMGeneratorMutiChannel { + public: + typedef function ontimirq_t; + + private: + zchip_tim_t *m_htim; + bool m_polarity; + float m_freq; + + bool m_pwmstate[4] = {0}; + + public: + ZPWMGeneratorMutiChannel() {} + + /** + * @brief + * + * @param Channel PWM通道 TIM_CHANNEL_1 TIM_CHANNEL_2 TIM_CHANNEL_3 TIM_CHANNEL_4 + * @param Polarity 1:高为有效电平,0:低为有效电平 + */ + void initialize(zchip_tim_t *htim, float freq, bool polarity); + /******************************************************************************* + * PWM_MODE * + *******************************************************************************/ + void startPWM(int32_t channelindex /*1,2,3,4*/, float duty); + void stopPWM(int32_t channelindex); + bool isPWMStart(int32_t channelindex); + + private: + void updatePWMState(int32_t channelindex /*1,2,3,4*/, float duty); +}; + +} // namespace iflytop + +#endif \ No newline at end of file diff --git a/components/algorithm/pid_module.cpp b/components/algorithm/pid_module.cpp new file mode 100644 index 0000000..c948a31 --- /dev/null +++ b/components/algorithm/pid_module.cpp @@ -0,0 +1,66 @@ + +#include "pid_module.hpp" + +using namespace iflytop; + +#define MIN(a, b) ((a) < (b) ? (a) : (b)) +#define MAX(a, b) ((a) > (b) ? (a) : (b)) + +void PidModule::initialize(config_t *cfg) { + m_cfg.kp = cfg->kp; + m_cfg.ki = cfg->ki; + m_cfg.kd = cfg->kd; + m_cfg.max_output = cfg->max_output; + m_cfg.min_output = cfg->min_output; + m_cfg.max_integral = cfg->max_integral; + m_cfg.min_integral = cfg->min_integral; +} + +int32_t PidModule::reset() { + m_last_output = 0; + m_previous_err1 = 0; + m_previous_err2 = 0; + m_integral_err = 0; +} +float PidModule::pid_calc_incremental(float error) { + float output = 0; + + /* Calculate the pid control value by increment formula */ + /* du(k) = (e(k)-e(k-1))*Kp + (e(k)-2*e(k-1)+e(k-2))*Kd + e(k)*Ki */ + /* u(k) = du(k) + u(k-1) */ + output = (error - m_previous_err1) * m_cfg.kp + (error - 2 * m_previous_err1 + m_previous_err2) * m_cfg.kd + error * m_cfg.ki + m_last_output; + + /* If the output is beyond the range, it will be limited */ + output = MIN(output, m_cfg.max_output); + output = MAX(output, m_cfg.min_output); + + /* Update previous error */ + m_previous_err2 = m_previous_err1; + m_previous_err1 = error; + + /* Update last output */ + m_last_output = output; + + return output; +} + +int32_t PidModule::compute(float input_error, float *ret_result) { + *ret_result = pid_calc_incremental(input_error); + return 0; +} + +void PidModule::update_kp(float v) { m_cfg.kp = v; } +void PidModule::update_ki(float v) { m_cfg.ki = v; } +void PidModule::update_kd(float v) { m_cfg.kd = v; } +void PidModule::update_max_output(float v) { m_cfg.max_output = v; } +void PidModule::update_min_output(float v) { m_cfg.min_output = v; } +void PidModule::update_max_integral(float v) { m_cfg.max_integral = v; } +void PidModule::update_min_integral(float v) { m_cfg.min_integral = v; } + +PidModule::config_t *PidModule::get_cfg() { return &m_cfg; } + +float PidModule::get_integral_err() { return m_integral_err; } +void PidModule::set_integral_err(float v) { m_integral_err = v; } + +float PidModule::get_integral_err() { return m_integral_err; } +float PidModule::get_output() { return m_last_output; } diff --git a/components/algorithm/pid_module.hpp b/components/algorithm/pid_module.hpp new file mode 100644 index 0000000..5dd3776 --- /dev/null +++ b/components/algorithm/pid_module.hpp @@ -0,0 +1,54 @@ +#pragma once +#include + +#include + +#include "sdk\components\zprotocols\zcancmder_v2\api\errorcode.hpp" + +namespace iflytop { +using namespace std; +class PidModule { + public: + typedef struct { + public: + float kp; // PID Kp parameter + float ki; // PID Ki parameter + float kd; // PID Kd parameter + float max_output; // PID maximum output limitation + float min_output; // PID minimum output limitation + float max_integral; // PID maximum integral value limitation + float min_integral; // PID minimum integral value limitation + } config_t; + + config_t m_cfg; + float m_last_output = 0; + float m_previous_err1 = 0; + float m_previous_err2 = 0; + float m_integral_err = 0; + + public: + void initialize(config_t *cfg); + + int32_t reset(); + int32_t compute(float input_error, float *ret_result); + + void update_kp(float v); + void update_ki(float v); + void update_kd(float v); + void update_max_output(float v); + void update_min_output(float v); + void update_max_integral(float v); + void update_min_integral(float v); + + float get_integral_err(); + float get_output(); + + config_t *get_cfg(); + + float get_integral_err(); + void set_integral_err(float v); + + private: + float pid_calc_incremental(float error); +}; +} // namespace iflytop \ No newline at end of file diff --git a/components/api/zi_fan_ctrl_module.hpp b/components/api/zi_fan_ctrl_module.hpp new file mode 100644 index 0000000..321a715 --- /dev/null +++ b/components/api/zi_fan_ctrl_module.hpp @@ -0,0 +1,16 @@ +#pragma once +#include + +#include + +#include "sdk\components\zprotocols\zcancmder_v2\api\errorcode.hpp" + +namespace iflytop { +using namespace std; +class ZIFanCtrlModule { + public: + virtual ~ZIFanCtrlModule() {} + + virtual void setFanSpeed(int32_t duty) = 0; +}; +} // namespace iflytop \ No newline at end of file diff --git a/components/api/zi_temperature_sensor.hpp b/components/api/zi_temperature_sensor.hpp new file mode 100644 index 0000000..ba5031a --- /dev/null +++ b/components/api/zi_temperature_sensor.hpp @@ -0,0 +1,15 @@ +#pragma once +#include + +#include + +#include "sdk\components\zprotocols\zcancmder_v2\api\errorcode.hpp" + +namespace iflytop { +using namespace std; +class ZITemperatureSensor { + public: + virtual ~ZITemperatureSensor() {} + virtual float getTemperature() = 0; // 摄氏度 +}; +} // namespace iflytop \ No newline at end of file diff --git a/components/sensors/tmp117/tmp117.cpp b/components/sensors/tmp117/tmp117.cpp new file mode 100644 index 0000000..fde6359 --- /dev/null +++ b/components/sensors/tmp117/tmp117.cpp @@ -0,0 +1,92 @@ +#include "tmp117.hpp" +using namespace iflytop; + +#define IF_FAIL_RETURN_VOID(func) \ + m_lastCallStatus = func; \ + if (m_lastCallStatus != HAL_OK) { \ + return; \ + } + +#define IF_FAIL_RETURN0(func) \ + m_lastCallStatus = func; \ + if (m_lastCallStatus != HAL_OK) { \ + return 0; \ + } + +TMP117::TMP117(/* args */) {} +TMP117::~TMP117() {} + +void TMP117::initializate(I2C_HandleTypeDef* i2c, ID_t id) { + m_i2c = i2c; + m_id = id; + m_lastCallStatus = HAL_OK; + + setConfiguration(0x0220); + setTemperatureOffset(0x0000); +} + +const char* TMP117::getLastCallStatusString() { + switch (m_lastCallStatus) { + case HAL_OK: + return "HAL_OK"; + case HAL_ERROR: + return "HAL_ERROR"; + case HAL_BUSY: + return "HAL_BUSY"; + case HAL_TIMEOUT: + return "HAL_TIMEOUT"; + default: + return "UNKNOWN"; + } +} + +float TMP117::getTemperature() { + uint8_t buf[3]; + buf[0] = TemperatureRegister; + + IF_FAIL_RETURN0(HAL_I2C_Master_Transmit(m_i2c, (uint16_t)m_id, buf, 1, 10)); + HAL_Delay(1); + IF_FAIL_RETURN0(HAL_I2C_Master_Receive(m_i2c, (uint16_t)m_id, buf, 2, 10)); + HAL_Delay(1); + return ((((buf[0] << 8) | buf[1])) * 0.0078125); +} +uint16_t TMP117::getConfiguration() { + uint8_t buf[3]; + buf[0] = ConfigurationRegister; + + IF_FAIL_RETURN0(HAL_I2C_Master_Transmit(m_i2c, (uint16_t)m_id, buf, 1, 10)); + HAL_Delay(1); + IF_FAIL_RETURN0(HAL_I2C_Master_Receive(m_i2c, (uint16_t)m_id, buf, 2, 10)); + HAL_Delay(1); + return ((buf[0] << 8) | buf[1]); +} +void TMP117::setConfiguration(uint16_t value) { + static uint8_t buf[3]; + buf[0] = ConfigurationRegister; + buf[1] = (value >> 8) & 0x0f; + buf[2] = value & 0x0f; + + IF_FAIL_RETURN_VOID(HAL_I2C_Master_Transmit(m_i2c, (uint16_t)m_id, buf, 2, 10)); + HAL_Delay(1); +} +void TMP117::setTemperatureOffset(uint16_t tempoffset) { // + setTemperatureOffset((tempoffset >> 8) & 0x0f, tempoffset & 0x0f); +} +void TMP117::setTemperatureOffset(uint8_t first, uint8_t second) { + static uint8_t buf[3]; + buf[0] = Temperature_Offset; + buf[1] = first; + buf[2] = second; + + IF_FAIL_RETURN_VOID(HAL_I2C_Master_Transmit(m_i2c, (uint16_t)m_id, buf, 2, 10)); + HAL_Delay(1); +} +uint16_t TMP117::getTemperatureOffset() { + static uint8_t buf[3]; + buf[0] = Temperature_Offset; + IF_FAIL_RETURN0(HAL_I2C_Master_Transmit(m_i2c, (uint16_t)m_id, buf, 1, 10)); + HAL_Delay(1); + IF_FAIL_RETURN0(HAL_I2C_Master_Receive(m_i2c, (uint16_t)m_id, buf, 2, 10)); + HAL_Delay(1); + return ((buf[0] << 8) | buf[1]); +} diff --git a/components/sensors/tmp117/tmp117.hpp b/components/sensors/tmp117/tmp117.hpp new file mode 100644 index 0000000..854f331 --- /dev/null +++ b/components/sensors/tmp117/tmp117.hpp @@ -0,0 +1,99 @@ +#pragma once +/** + * @file tmp117.hpp + * @author zhaohe (h_zhaohe@163.com) + * @brief + * @version 0.1 + * @date 2023-04-14 + * + * @copyright Copyright (c) 2023 + * + * + * 1. 参考:https://github.com/rkiyak/TMP117.git + * 2. 同级目录有芯片的datasheet。 + */ +#include + +#include "sdk/os/zos.hpp" +#include "sdk\components\api\zi_temperature_sensor.hpp" + +#ifdef HAL_I2C_MODULE_ENABLED +namespace iflytop { + +class TMP117 : public ZITemperatureSensor { + public: + typedef enum { + ID0 = 0x48 << 1, // GND + ID1 = 0x49 << 1, // Vcc + ID2 = 0x4A << 1, // SDA + ID3 = 0x4B << 1, // SCL + } ID_t; + + typedef enum { + TemperatureRegister = 0x00, + ConfigurationRegister = 0x01, + TemperatureHighLimit = 0x02, + TemperatureLowLimit = 0x03, + + EEPROM_Uclock = 0x04, + EEPROM1 = 0x05, + EEPROM2 = 0x06, + EEPROM3 = 0x08, + + Temperature_Offset = 0x07, + ID_Register = 0x0F, + } REGADD_t; + + private: + /* data */ + I2C_HandleTypeDef* m_i2c; + ID_t m_id; + + HAL_StatusTypeDef m_lastCallStatus; + + public: + TMP117(/* args */); + ~TMP117(); + + /** + * @brief 初始化 + * + * @param i2c + * @param id + */ + void initializate(I2C_HandleTypeDef* i2c, ID_t id); + + /** + * @brief 读取温度 + * + * @return float + */ + virtual float getTemperature() override; + + /** + * @brief 获取最后一次调用的状态 + * + * @return HAL_StatusTypeDef + */ + HAL_StatusTypeDef getLastCallStatus() { return m_lastCallStatus; }; + const char* getLastCallStatusString(); + + /******************************************************************************* + * 扩展使用 * + *******************************************************************************/ + /** + * @brief 下面相关方法需要阅读芯片datasheet来使用,一般情况下不会用到 + */ + + uint16_t getConfiguration(); + void setConfiguration(uint16_t value); + void setTemperatureOffset(uint8_t first, uint8_t second); + void setTemperatureOffset(uint16_t tempoffset); + uint16_t getTemperatureOffset(); + uint16_t getIdRegister(); + + private: +}; + +} // namespace iflytop +#endif diff --git a/components/sensors/tmp117/tmp117.pdf b/components/sensors/tmp117/tmp117.pdf new file mode 100644 index 0000000..74ff960 Binary files /dev/null and b/components/sensors/tmp117/tmp117.pdf differ diff --git a/components/ti/drv8710.cpp b/components/ti/drv8710.cpp new file mode 100644 index 0000000..2487c1a --- /dev/null +++ b/components/ti/drv8710.cpp @@ -0,0 +1,46 @@ +#include "drv8710.hpp" +using namespace iflytop; + +void DRV8710::initialize(hardware_cfg_t* cfg) { // + m_cfg = *cfg; + m_pwmCtrl.initialize(cfg->tim, 10 * 000, false); + + m_nsleep.initAsOutput(cfg->nsleep, ZGPIO::kMode_nopull, false, false); + m_nfault.initAsInput(cfg->nfault, ZGPIO::kMode_pullup, ZGPIO::kIRQ_noIrq, false); + m_in2.initAsOutput(cfg->in2, ZGPIO::kMode_nopull, false, false); + enable(false); +} + +void DRV8710::moveForward(int32_t duty) { + if (duty > 100) duty = 100; + if (duty < 0) duty = 0; + + set_direcetion(true); + m_pwmCtrl.startPWM(m_cfg.in1_chnannel_index, duty); +} +void DRV8710::moveBackward(int32_t duty) { + if (duty > 100) duty = 100; + if (duty < 0) duty = 0; + + set_direcetion(false); + m_pwmCtrl.startPWM(m_cfg.in1_chnannel_index, duty); +} + +bool DRV8710::isFault() { return !m_nfault.getState(); } + +void DRV8710::move(int32_t duty) { + if (duty >= 0) { + moveForward(duty); + } else if (duty < 0) { + moveBackward(-duty); + } +} + +void DRV8710::set_direcetion(bool direcetion) { + if (m_cfg.shaft) { + direcetion = !direcetion; + } + m_in2.setState(direcetion); +} + +void DRV8710::enable(bool varenable) { m_nsleep.setState(varenable); } diff --git a/components/ti/drv8710.hpp b/components/ti/drv8710.hpp new file mode 100644 index 0000000..5f14fc9 --- /dev/null +++ b/components/ti/drv8710.hpp @@ -0,0 +1,68 @@ +#pragma once +/** + * @file tmp117.hpp + * @author zhaohe (h_zhaohe@163.com) + * @brief + * @version 0.1 + * @date 2023-04-14 + * + * @copyright Copyright (c) 2023 + * + * + * 1. 参考:https://github.com/rkiyak/TMP117.git + * 2. 同级目录有芯片的datasheet。 + */ +#include + +#include "sdk/os/zos.hpp" +#include "sdk\chip\zpwm_generator_muti_channel.hpp" +// + +namespace iflytop { +// SUPPORT REG + +/** + * @brief Cubemx配置 + * + * 1. 使能一个定时器,将In1引脚配置成PWM引脚 + */ +class DRV8710 { + public: + typedef struct { + TIM_HandleTypeDef* tim; + int32_t in1_chnannel_index; + + Pin_t in2; + Pin_t nsleep; + Pin_t nfault; + bool shaft; + } hardware_cfg_t; + + ZPWMGeneratorMutiChannel m_pwmCtrl; + + ZGPIO m_in2; + ZGPIO m_nsleep; + ZGPIO m_nfault; + + hardware_cfg_t m_cfg; + // ZGPIO so; + + public: + DRV8710(){}; + + void initialize(hardware_cfg_t* cfg); + + void enable(bool varenable); + + void moveForward(int32_t duty); // 0->100 + void moveBackward(int32_t duty); // 0->100 + + void move(int32_t duty); // -100->100 + + bool isFault(); + + private: + void set_direcetion(bool direcetion); +}; + +} // namespace iflytop diff --git a/components/water_cooling_temperature_control_module/peltier_contrler.cpp b/components/water_cooling_temperature_control_module/peltier_contrler.cpp new file mode 100644 index 0000000..e69de29 diff --git a/components/water_cooling_temperature_control_module/peltier_contrler.hpp b/components/water_cooling_temperature_control_module/peltier_contrler.hpp new file mode 100644 index 0000000..b578b81 --- /dev/null +++ b/components/water_cooling_temperature_control_module/peltier_contrler.hpp @@ -0,0 +1,24 @@ +#pragma once +/** + * @file tmp117.hpp + * @author zhaohe (h_zhaohe@163.com) + * @brief + * @version 0.1 + * @date 2023-04-14 + * + * @copyright Copyright (c) 2023 + * + * + */ +#include + +#include "sdk/os/zos.hpp" +#include "sdk\chip\zpwm_generator_muti_channel.hpp" +// + +namespace iflytop { +// SUPPORT REG + + + +} // namespace iflytop diff --git a/components/water_cooling_temperature_control_module/pwm_ctrl_module.cpp b/components/water_cooling_temperature_control_module/pwm_ctrl_module.cpp new file mode 100644 index 0000000..4d854e1 --- /dev/null +++ b/components/water_cooling_temperature_control_module/pwm_ctrl_module.cpp @@ -0,0 +1,129 @@ +#include "pwm_ctrl_module.hpp" + +#include "sdk\components\zprotocols\zcancmder_v2\api\errorcode.hpp" +using namespace iflytop; + +void PWMSpeedCtrlModule::initialize(fangroup_device_cfg_t* pcfg, bool enablefbcheck) { + ZASSERT(pcfg); + ZASSERT(pcfg->fanCtrlTim); + cfg = *pcfg; + m_enablefbcheck = enablefbcheck; + + if (m_enablefbcheck) { + for (int32_t i = 0; i < ZARRAY_SIZE(cfg.fanFBGpioCfg); i++) { + if (cfg.fanFBGpioCfg[i].pin != PinNull) { + m_fanFBGpio[i].initAsInput(cfg.fanFBGpioCfg[i].pin, // + cfg.fanFBGpioCfg[i].mode, // + ZGPIO::kIRQ_risingIrq, // + cfg.fanFBGpioCfg[i].mirror); + m_fanFBGpio[i].regListener([this, i](ZGPIO* GPIO_Pin, ZGPIO::IrqTypeEvent_t irqevent) { onfbgpioirq(i); }); + m_nfanFBGpio++; + } + } + } + + for (int32_t i = 0; i < ZARRAY_SIZE(cfg.fanPowerGpioCfg); i++) { + if (cfg.fanPowerGpioCfg[i].pin != PinNull) { + m_fanPowerGpio[i].initAsOutput(cfg.fanPowerGpioCfg[i].pin, // + cfg.fanPowerGpioCfg[i].mode, // + cfg.fanPowerGpioCfg[i].initLevel, // + cfg.fanPowerGpioCfg[i].mirror); + m_nfanPowerPin++; + } + } + m_fanCtrlPwm.initialize(cfg.fanCtrlTim, 1000, false); + ZASSERT(pcfg->nfan == m_nfanFBGpio); +} + +void PWMSpeedCtrlModule::onfbgpioirq(int32_t fanindex) { + // IRQ Context,中断上下文 + m_fanstate[fanindex].fanFBCount++; + m_fanstate[fanindex].lastupdateFanFBCountTime = zos_get_tick(); +} + +int32_t PWMSpeedCtrlModule::startModule(int32_t duty) { + if (duty < 20) duty = 20; + fanisworking = true; + + clearError(); + startFanPWM(duty); + powerON(); + m_lastcheckTime = zos_get_tick(); +} +int32_t PWMSpeedCtrlModule::stopModule() { + fanisworking = false; + stopFanPWM(); + powerOff(); +} + +int32_t PWMSpeedCtrlModule::getSubModuleErrorState(int32_t fanindex, int32_t* error_state) { + if (fanindex > 3) { + return err::kfail; + } + + *error_state = m_fanstate[fanindex].fanerrorstate; + return 0; +} + +bool PWMSpeedCtrlModule::isError() { + bool iserror = false; + for (int32_t i = 0; i < cfg.nfan; i++) { + if (m_fanstate[i].fanerrorstate > 0) { + iserror = true; + break; + } + } + return iserror; +} + +void PWMSpeedCtrlModule::checkfanState() { + if (!m_enablefbcheck) return; + + if (zos_haspassedms(m_lastcheckTime) < 10 * 1000) { + return; + } + + m_lastcheckTime = zos_get_tick(); + for (int32_t i = 0; i < cfg.nfan; i++) { + checkfanState(i); + } +} + +void PWMSpeedCtrlModule::checkfanState(int32_t fanindex) { + if (fanisworking && zos_haspassedms(m_fanstate[fanindex].lastupdateFanFBCountTime) > 10 * 1000) { + m_fanstate[fanindex].fanerrorstate = 1; + powerOff(); + } +} + +void PWMSpeedCtrlModule::powerON() { + for (int32_t i = 0; i < m_nfanPowerPin; i++) { + m_fanPowerGpio[i].setState(true); + } +} +void PWMSpeedCtrlModule::powerOff() { + for (int32_t i = 0; i < m_nfanPowerPin; i++) { + m_fanPowerGpio[i].setState(false); + } +} + +void PWMSpeedCtrlModule::clearError() { + for (int32_t i = 0; i < cfg.nfan; i++) { + m_fanstate[i].fanerrorstate = 0; + } +} + +void PWMSpeedCtrlModule::startFanPWM(int32_t duty) { + for (int32_t i = 0; i < ZARRAY_SIZE(cfg.fan0Channel); i++) { + if (cfg.fan0Channel[i] != 0) { + m_fanCtrlPwm.startPWM(cfg.fan0Channel[i], duty); + } + } +} +void PWMSpeedCtrlModule::stopFanPWM() { + for (int32_t i = 0; i < ZARRAY_SIZE(cfg.fan0Channel); i++) { + if (cfg.fan0Channel[i] != 0) { + m_fanCtrlPwm.stopPWM(cfg.fan0Channel[i]); + } + } +} \ No newline at end of file diff --git a/components/water_cooling_temperature_control_module/pwm_ctrl_module.hpp b/components/water_cooling_temperature_control_module/pwm_ctrl_module.hpp new file mode 100644 index 0000000..3f11aad --- /dev/null +++ b/components/water_cooling_temperature_control_module/pwm_ctrl_module.hpp @@ -0,0 +1,81 @@ +#pragma once +/** + * @file tmp117.hpp + * @author zhaohe (h_zhaohe@163.com) + * @brief + * @version 0.1 + * @date 2023-04-14 + * + * @copyright Copyright (c) 2023 + * + * + * 1. 参考:https://github.com/rkiyak/TMP117.git + * 2. 同级目录有芯片的datasheet。 + */ +#include + +#include "sdk/os/zos.hpp" +#include "sdk\chip\zpwm_generator_muti_channel.hpp" +// + +namespace iflytop { +// SUPPORT REG + +class PWMSpeedCtrlModule { + public: + typedef struct { + TIM_HandleTypeDef* fanCtrlTim; + int32_t nfan; + int32_t fan0Channel[4]; + ZGPIO::InputGpioCfg_t fanFBGpioCfg[4]; + ZGPIO::OutputGpioCfg_t fanPowerGpioCfg[4]; + } fangroup_device_cfg_t; + + typedef struct { + int32_t fanFBCount; + uint32_t lastupdateFanFBCountTime; + int32_t fanerrorstate; + } fanState_t; + + ZPWMGeneratorMutiChannel m_fanCtrlPwm; + + ZGPIO m_fanFBGpio[4]; + int32_t m_nfanFBGpio = 0; + + ZGPIO m_fanPowerGpio[4]; + int32_t m_nfanPowerPin = 0; + + fanState_t m_fanstate[4]; + bool fanisworking = false; + uint32_t m_lastcheckTime = 0; + + fangroup_device_cfg_t cfg; + + bool m_enablefbcheck = false; + + public: + PWMSpeedCtrlModule(){}; + + void initialize(fangroup_device_cfg_t* fangroup, bool enablefbcheck = false); + + int32_t startModule(int32_t duty); + int32_t stopModule(); + + int32_t getSubModuleErrorState(int32_t fanindex, int32_t* error_state); + bool isError(); + + void checkfanState(); + + private: + void onfbgpioirq(int32_t fanindex); + + private: + void checkfanState(int32_t fanindex); + void powerON(); + void powerOff(); + void clearError(); + void startFanPWM(int32_t duty); + void stopFanPWM(); +}; + +} // namespace iflytop diff --git a/components/water_cooling_temperature_control_module/water_cooling_temperature_control_module.cpp b/components/water_cooling_temperature_control_module/water_cooling_temperature_control_module.cpp new file mode 100644 index 0000000..a2d7fb0 --- /dev/null +++ b/components/water_cooling_temperature_control_module/water_cooling_temperature_control_module.cpp @@ -0,0 +1,273 @@ +#include "water_cooling_temperature_control_module.hpp" + +#include "sdk\components\flash\znvs.hpp" +#include "sdk\components\zprotocols\zcancmder_v2\api\api.hpp" + +using namespace iflytop; + +#define TAG "WaterCoolingTemperatureControlModule" + +void WaterCoolingTemperatureControlModule::initialize(config_t* cfg, // + ZITemperatureSensor** temperature_sensor, int32_t ntemperature, // + DRV8710** m_peltier_ctrl, int32_t m_peltier_ctrl_num, // + PWMSpeedCtrlModule** fan, int32_t nfan, // + PWMSpeedCtrlModule* pump // +) { + ZASSERT(ntemperature < 4); + + m_n_temperature_sensor = ntemperature; + m_fanNum = nfan; + + for (int32_t i = 0; i < ntemperature; i++) { + m_temperature_sensor[i] = temperature_sensor[i]; + ZASSERT(m_temperature_sensor[i]); + } + + for (int32_t i = 0; i < nfan; i++) { + m_fanTable[i] = fan[i]; + ZASSERT(m_fanTable[i]); + } + + m_pump = pump; + + m_pidmodule.initialize(&cfg->pid_cfg); + m_thread.init("WaterCoolingTemperatureControlModule"); + + ZLOGI(TAG, "WaterCoolingTemperatureControlModule initialized..."); +} + +void WaterCoolingTemperatureControlModule::createDefaultConfig(config_t* cfg) { + cfg->fanlevel = 90; + cfg->pumplevel = 90; + cfg->pid_cfg.kp = 9; + cfg->pid_cfg.ki = 0.600; + cfg->pid_cfg.kd = 0; + cfg->pid_cfg.max_output = 90; + cfg->pid_cfg.min_output = -90; + cfg->pid_cfg.max_integral = 100; + cfg->pid_cfg.min_integral = -100; + cfg->pidcompute_periodms = 1000; +} +#define SET_REG(param_id, modulereg, precision) \ + case param_id: \ + modulereg = param_value * precision; \ + break; + +#define GET_REG(param_id, modulereg, precision) \ + case param_id: \ + *param_value = modulereg / precision; \ + break; + +#if 0 + kreg_pid_kp = REG_INDEX(3000, 0), // kp + kreg_pid_ki = REG_INDEX(3000, 1), // ki + kreg_pid_kd = REG_INDEX(3000, 2), // kd + kreg_pid_max_output = REG_INDEX(3000, 3), // 最大输出 + kreg_pid_min_output = REG_INDEX(3000, 4), // 最小输出 + kreg_pid_max_integral = REG_INDEX(3000, 5), // 最大积分 + kreg_pid_min_integral = REG_INDEX(3000, 6), // 最小积分 + kreg_error_limit = REG_INDEX(3000, 7), // 误差限制 + kreg_compute_interval = REG_INDEX(3000, 8), // 计算间隔 + + kreg_pid_target = REG_INDEX(3050, 0), // 目标数值 + kreg_pid_nowoutput = REG_INDEX(3050, 1), // 当前输出 + kreg_pid_feedbackval = REG_INDEX(3050, 2), // 当前输出 + +#endif + +int32_t WaterCoolingTemperatureControlModule::module_set_reg(int32_t param_id, int32_t param_value) { + switch (param_id) { + SET_REG(kreg_pid_kp, m_cfg.pid_cfg.kp, 0.01); + SET_REG(kreg_pid_ki, m_cfg.pid_cfg.ki, 0.01); + SET_REG(kreg_pid_kd, m_cfg.pid_cfg.kd, 0.01); + SET_REG(kreg_pid_max_output, m_cfg.pid_cfg.max_output, 1); + SET_REG(kreg_pid_min_output, m_cfg.pid_cfg.min_output, 1); + SET_REG(kreg_pid_max_integral, m_cfg.pid_cfg.max_integral, 1); + SET_REG(kreg_pid_min_integral, m_cfg.pid_cfg.min_integral, 1); + SET_REG(kreg_compute_interval, m_cfg.pidcompute_periodms, 1); + SET_REG(kreg_pid_target, m_target_temperature, 0.1); + SET_REG(kreg_fan0_ctrl_speed_level, m_cfg.fanlevel, 1); + SET_REG(kreg_pwm_pump0_ctrl_speed_level, m_cfg.pumplevel, 1); + default: + return err::kmodule_not_find_config_index; + } + return 0; +} +int32_t WaterCoolingTemperatureControlModule::module_get_reg(int32_t param_id, int32_t* param_value) { + switch (param_id) { + GET_REG(kreg_pid_kp, m_cfg.pid_cfg.kp, 0.01); + GET_REG(kreg_pid_ki, m_cfg.pid_cfg.ki, 0.01); + GET_REG(kreg_pid_kd, m_cfg.pid_cfg.kd, 0.01); + GET_REG(kreg_pid_max_output, m_cfg.pid_cfg.max_output, 1); + GET_REG(kreg_pid_min_output, m_cfg.pid_cfg.min_output, 1); + GET_REG(kreg_pid_max_integral, m_cfg.pid_cfg.max_integral, 1); + GET_REG(kreg_pid_min_integral, m_cfg.pid_cfg.min_integral, 1); + GET_REG(kreg_compute_interval, m_cfg.pidcompute_periodms, 1); + GET_REG(kreg_pid_target, m_target_temperature, 0.1); + GET_REG(kreg_pid_nowoutput, m_pidmodule.get_output(), 1); + GET_REG(kreg_pid_feedbackval, read_pid_temperature(), 1); + + GET_REG(kreg_module_version, 0, 1); + GET_REG(kreg_module_type, 0, 1); + GET_REG(kreg_module_status, getworkstate(), 1); + GET_REG(kreg_module_errorcode, m_errorcode, 1); + GET_REG(kreg_module_initflag, module_get_inited_flag(), 1); + GET_REG(kreg_module_errorbitflag0, geterrorbitflag0(), 1); + GET_REG(kreg_module_errorbitflag1, geterrorbitflag1(), 1); + + GET_REG(kreg_sensor_temperature0, getTemperatureSensorVal(0), 0.1); + GET_REG(kreg_sensor_temperature1, getTemperatureSensorVal(1), 0.1); + GET_REG(kreg_sensor_temperature2, getTemperatureSensorVal(2), 0.1); + GET_REG(kreg_sensor_temperature3, getTemperatureSensorVal(3), 0.1); + + GET_REG(kreg_fan0_ctrl_speed_level, m_cfg.fanlevel, 1); + GET_REG(kreg_pwm_pump0_ctrl_speed_level, m_cfg.pumplevel, 1); + default: + return err::kmodule_not_find_config_index; + } + return 0; +} + +int32_t WaterCoolingTemperatureControlModule::module_factory_reset() { return 0; } +int32_t WaterCoolingTemperatureControlModule::module_flush_cfg() { return 0; } +int32_t WaterCoolingTemperatureControlModule::module_active_cfg() { return 0; } + +int32_t WaterCoolingTemperatureControlModule::module_stop() { + m_thread.stop(); + return 0; +} +int32_t WaterCoolingTemperatureControlModule::module_start() { + m_thread.stop(); + m_errorcode = 0; + ZLOGI(TAG, "module_start"); + m_thread.start([this]() { workloop(); }); + return 0; +} +int32_t WaterCoolingTemperatureControlModule::module_break() { + m_thread.stop(); + return 0; +} + +void WaterCoolingTemperatureControlModule::workloop() { + /** + * @brief + * 启动水泵 + * 启动风扇 + * 初始化PID模块 + * + * while(true){ + * 1.采集温度 + * 2.控制制冷片功率 + * } + */ + + pump_start(m_cfg.pumplevel); + fan_start(m_cfg.fanlevel); + + while (!m_thread.getExitFlag()) { + if (checkdevice() != 0) { + ZLOGE(TAG, "somedevice is not working, stop the module"); + break; + } + + m_thread.sleep(m_cfg.pidcompute_periodms); + + float val = read_pid_temperature(); + + float error = m_target_temperature - val; + float out = 0; + m_pidmodule.compute(error, &out); + + ZLOGI(TAG, "temperature: %.2f %.2f integral_err:%.2f out:%d", m_target_temperature, val, m_pidmodule.get_integral_err(), (int32_t)out); + peltier_set_power_level(out); + } + + pump_stop(); + fan_stop(); +} + +int32_t WaterCoolingTemperatureControlModule::checkdevice() { return 0; } + +/******************************************************************************* + * BASIC * + *******************************************************************************/ + +float WaterCoolingTemperatureControlModule::read_pid_temperature() { return m_temperature_sensor[0]->getTemperature(); } + +void WaterCoolingTemperatureControlModule::pump_start(int32_t pump_speed) { + ZLOGI(TAG, "pump_start %d", pump_speed); + m_pump->startModule(pump_speed); +} +void WaterCoolingTemperatureControlModule::pump_stop() { + ZLOGI(TAG, "pump_stop"); + m_pump->stopModule(); +} + +void WaterCoolingTemperatureControlModule::fan_start(int32_t pump_speed) { + ZLOGI(TAG, "fan_start %d", pump_speed); + for (int32_t i = 0; i < m_fanNum; i++) { + m_fanTable[i]->startModule(pump_speed); + } +} +void WaterCoolingTemperatureControlModule::fan_stop() { + ZLOGI(TAG, "fan_stop"); + for (int32_t i = 0; i < m_fanNum; i++) { + m_fanTable[i]->stopModule(); + } +} + +void WaterCoolingTemperatureControlModule::peltier_set_power_level(int32_t level) { + ZLOGI(TAG, "peltier_set_power_level %d", level); + for (int32_t i = 0; i < m_peltier_ctrl_num; i++) { + m_peltier_ctrl[i]->move(level); + m_peltier_ctrl[i]->enable(true); + } +} +void WaterCoolingTemperatureControlModule::peltier_stop() { + ZLOGI(TAG, "peltier_stop"); + for (int32_t i = 0; i < m_peltier_ctrl_num; i++) { + m_peltier_ctrl[i]->move(0); + m_peltier_ctrl[i]->enable(false); + } +} + +int32_t WaterCoolingTemperatureControlModule::getworkstate() { + if (m_errorcode != 0) { + return 2; + } + + if (!m_thread.isworking()) { + return 0; + } else { + return 1; + } +} + +int32_t WaterCoolingTemperatureControlModule::geterrorbitflag0() { + /** + * @brief + * + * bit 0->3 fan0,fan1,fan2,fan3, + * bit 4->4 pump0, + * bit 8->9 peltier0_controler,peltier1_controler + */ + int32_t errorbitflag = 0; + if (m_fanTable[0]) errorbitflag |= m_fanTable[0]->isError() << 0; + if (m_fanTable[1]) errorbitflag |= m_fanTable[1]->isError() << 1; + if (m_fanTable[2]) errorbitflag |= m_fanTable[2]->isError() << 2; + if (m_fanTable[3]) errorbitflag |= m_fanTable[3]->isError() << 3; + + if (m_pump) errorbitflag |= m_pump->isError() << 4; + + if (m_peltier_ctrl[0]) errorbitflag |= m_peltier_ctrl[0]->isFault() << 8; + if (m_peltier_ctrl[1]) errorbitflag |= m_peltier_ctrl[1]->isFault() << 9; + return errorbitflag; +} +int32_t WaterCoolingTemperatureControlModule::geterrorbitflag1() { return 0; } + +float WaterCoolingTemperatureControlModule::getTemperatureSensorVal(int32_t index) { + if (index < 0 || index >= m_n_temperature_sensor) { + return 0; + } + return m_temperature_sensor[index]->getTemperature(); +} diff --git a/components/water_cooling_temperature_control_module/water_cooling_temperature_control_module.hpp b/components/water_cooling_temperature_control_module/water_cooling_temperature_control_module.hpp new file mode 100644 index 0000000..2728c1a --- /dev/null +++ b/components/water_cooling_temperature_control_module/water_cooling_temperature_control_module.hpp @@ -0,0 +1,163 @@ +#pragma once +/** + * @file tmp117.hpp + * @author zhaohe (h_zhaohe@163.com) + * @brief + * @version 0.1 + * @date 2023-04-14 + * + * @copyright Copyright (c) 2023 + * + * + * 1. 参考:https://github.com/rkiyak/TMP117.git + * 2. 同级目录有芯片的datasheet。 + */ +#include + +#include "sdk/os/zos.hpp" +// +#include "pwm_ctrl_module.hpp" +#include "sdk/components/api/zi_fan_ctrl_module.hpp" +#include "sdk\components\algorithm\pid_module.hpp" +#include "sdk\components\api\zi_temperature_sensor.hpp" +#include "sdk\components\ti\drv8710.hpp" +#include "sdk\components\zprotocols\zcancmder_v2\api\zi_module.hpp" + +namespace iflytop { +// SUPPORT REG +#if 0 + kreg_pid_kp = REG_INDEX(3000, 0), // kp + kreg_pid_ki = REG_INDEX(3000, 1), // ki + kreg_pid_kd = REG_INDEX(3000, 2), // kd + kreg_pid_max_output = REG_INDEX(3000, 3), // 最大输出 + kreg_pid_min_output = REG_INDEX(3000, 4), // 最小输出 + kreg_pid_max_integral = REG_INDEX(3000, 5), // 最大积分 + kreg_pid_min_integral = REG_INDEX(3000, 6), // 最小积分 + kreg_error_limit = REG_INDEX(3000, 7), // 误差限制 + kreg_compute_interval = REG_INDEX(3000, 8), // 计算间隔 + + kreg_pid_target = REG_INDEX(3050, 0), // 目标数值 + kreg_pid_nowoutput = REG_INDEX(3050, 1), // 当前输出 + kreg_pid_feedbackval = REG_INDEX(3050, 2), // 当前输出 + + kreg_module_version = REG_INDEX(0, 0), // 模块版本 + kreg_module_type = REG_INDEX(0, 1), // 模块类型 + kreg_module_status = REG_INDEX(0, 2), // 0idle,1busy,2error + kreg_module_errorcode = REG_INDEX(0, 3), // inited_flag + kreg_module_initflag = REG_INDEX(0, 4), // inited_flag + kreg_module_enableflag = REG_INDEX(0, 5), // 0idle,1busy,2error + kreg_module_errorbitflag0 = REG_INDEX(0, 6), // 模块异常标志,bit,每个模块自定义 + kreg_module_errorbitflag1 = REG_INDEX(0, 7), // + + kreg_sensor_temperature0 = REG_INDEX(2100, 0), // 温度1 + kreg_sensor_temperature1 = REG_INDEX(2100, 1), // 温度2 + kreg_sensor_temperature2 = REG_INDEX(2100, 2), // 温度3 + kreg_sensor_temperature3 = REG_INDEX(2100, 3), // 温度4 + + kreg_fan0_ctrl_speed_level = REG_INDEX(4000, 0), // 风扇转速0,1,2,3 + kreg_fan1_ctrl_speed_level = REG_INDEX(4000, 1), // 风扇转速0,1,2,3 + kreg_fan2_ctrl_speed_level = REG_INDEX(4000, 2), // 风扇转速0,1,2,3 + kreg_fan3_ctrl_speed_level = REG_INDEX(4000, 3), // 风扇转速0,1,2,3 + + kreg_fan0_speed_level = REG_INDEX(4010, 0), // 风扇实时转速0,1,2,3 + kreg_fan1_speed_level = REG_INDEX(4010, 1), // 风扇实时转速0,1,2,3 + kreg_fan2_speed_level = REG_INDEX(4010, 2), // 风扇实时转速0,1,2,3 + kreg_fan3_speed_level = REG_INDEX(4010, 3), // 风扇实时转速0,1,2,3 + + kreg_fan0_e_state = REG_INDEX(4010, 0), // 风扇是否工作正常 0:正常 1:异常 + kreg_fan1_e_state = REG_INDEX(4010, 1), // 风扇是否工作正常 0:正常 1:异常 + kreg_fan2_e_state = REG_INDEX(4010, 2), // 风扇是否工作正常 0:正常 1:异常 + kreg_fan3_e_state = REG_INDEX(4010, 3), // 风扇是否工作正常 0:正常 1:异常 +#endif + +/** + * @brief + * 水冷温度控制模块 + */ + +class WaterCoolingTemperatureControlModule : public ZIModule { + public: + typedef struct { + PidModule::config_t pid_cfg; + int32_t fanlevel; + int32_t pumplevel; + int32_t pidcompute_periodms; + } config_t; + + private: + config_t m_cfg; + int32_t m_id = 1; + + // 温度传感器 + ZITemperatureSensor* m_temperature_sensor[4] = {0}; + int32_t m_n_temperature_sensor = 0; + // 风扇 + PWMSpeedCtrlModule* m_fanTable[4] = {0}; + int32_t m_fanNum = 0; + // 水泵 + PWMSpeedCtrlModule* m_pump = nullptr; + // 帕尔贴控制器 + DRV8710* m_peltier_ctrl[2]; + int32_t m_peltier_ctrl_num = 0; + + // PID模块 + PidModule m_pidmodule; + // 模块ID + ZThread m_thread; + + float m_target_temperature = 0; + + int32_t m_errorcode = 0; + + public: + WaterCoolingTemperatureControlModule(){}; + + static void createDefaultConfig(config_t* cfg); + + void initialize(config_t* cfg, // + ZITemperatureSensor** temperature_sensor, int32_t ntemperature, // + DRV8710** m_peltier_ctrl, int32_t m_peltier_ctrl_num, // + PWMSpeedCtrlModule** fan, int32_t nfan, // + PWMSpeedCtrlModule* pump // + ); + + virtual int32_t getid(int32_t* id) override; + + virtual int32_t module_set_reg(int32_t param_id, int32_t param_value) override; + virtual int32_t module_get_reg(int32_t param_id, int32_t* param_value) override; + + virtual int32_t module_factory_reset() override; + virtual int32_t module_flush_cfg() override; + virtual int32_t module_active_cfg() override; + + virtual int32_t module_stop() override; + virtual int32_t module_start() override; + virtual int32_t module_break() override; + + private: + void workloop(); + + int32_t checkdevice(); + + float read_pid_temperature(); + + void pump_start(int32_t pump_speed); + void pump_stop(); + + void fan_start(int32_t pump_speed); + void fan_stop(); + + void peltier_set_power_level(int32_t level); + void peltier_stop(); + + void geterrorcode(); + + private: + int32_t getworkstate(); + int32_t geterrorbitflag0(); + int32_t geterrorbitflag1(); + + float getTemperatureSensorVal(int32_t index); +}; + +} // namespace iflytop diff --git a/components/zcancmder/zcanreceiver.cpp b/components/zcancmder/zcanreceiver.cpp index aa1303c..28c0bc1 100644 --- a/components/zcancmder/zcanreceiver.cpp +++ b/components/zcancmder/zcanreceiver.cpp @@ -38,7 +38,7 @@ void ZCanCmder::init(CFG *cfg) { * @brief 初始化消息接收buf */ m_canPacketRxBuffer[0].dataIsReady = false; - m_canPacketRxBuffer[0].id = 1; // 只接收来自主机的消息 + m_canPacketRxBuffer[0].id = 0; // 只接收来自主机的消息 m_canPacketRxBuffer[0].m_canPacketNum = 0; /** diff --git a/components/zcancmder/zcanreceiver_master.hpp b/components/zcancmder/zcanreceiver_master.hpp index ff909ad..e2447fe 100644 --- a/components/zcancmder/zcanreceiver_master.hpp +++ b/components/zcancmder/zcanreceiver_master.hpp @@ -21,7 +21,7 @@ class ZCanCommnaderMaster : public ZCanIRQListener, public IZcanCmderMaster { public: class CFG { public: - uint8_t deviceId; // + uint8_t deviceId = 0; // /******************************************************************************* * CANConfig * *******************************************************************************/ diff --git a/components/zprotocol_helper/micro_computer_module_device_script_cmder_paser.cpp b/components/zprotocol_helper/micro_computer_module_device_script_cmder_paser.cpp index 397bd18..97b6417 100644 --- a/components/zprotocol_helper/micro_computer_module_device_script_cmder_paser.cpp +++ b/components/zprotocol_helper/micro_computer_module_device_script_cmder_paser.cpp @@ -171,10 +171,10 @@ void MicroComputerModuleDeviceScriptCmderPaser::do_dumpreg(int32_t paramN, const DUMP_CONFIG("pid_kp", kreg_pid_kp); DUMP_CONFIG("pid_ki", kreg_pid_ki); DUMP_CONFIG("pid_kd", kreg_pid_kd); - DUMP_CONFIG("pid_max_max_output", kreg_pid_max_max_output); - DUMP_CONFIG("pid_max_min_output", kreg_pid_max_min_output); - DUMP_CONFIG("pid_max_max_integral", kreg_pid_max_max_integral); - DUMP_CONFIG("pid_max_min_integral", kreg_pid_max_min_integral); + DUMP_CONFIG("pid_max_max_output", kreg_pid_max_output); + DUMP_CONFIG("pid_max_min_output", kreg_pid_min_output); + DUMP_CONFIG("pid_max_max_integral", kreg_pid_max_integral); + DUMP_CONFIG("pid_max_min_integral", kreg_pid_min_integral); DUMP_CONFIG("error_limit", kreg_error_limit); DUMP_CONFIG("compute_interval", kreg_compute_interval); @@ -185,7 +185,6 @@ void MicroComputerModuleDeviceScriptCmderPaser::do_dumpreg(int32_t paramN, const /******************************************************************************* * 非标状态 * *******************************************************************************/ - DUMP_CONFIG("fan_cfg_speed_level", kreg_fan_cfg_speed_level); } void MicroComputerModuleDeviceScriptCmderPaser::initialize(ICmdParser* cancmder, ZModuleDeviceManager* deviceManager) { diff --git a/components/zprotocols/zcancmder_v2 b/components/zprotocols/zcancmder_v2 index eff8724..59fdf6a 160000 --- a/components/zprotocols/zcancmder_v2 +++ b/components/zprotocols/zcancmder_v2 @@ -1 +1 @@ -Subproject commit eff87241aaf65b433aab96b0d8a7ce0261c4d9dc +Subproject commit 59fdf6a80d2504ee170ea8921642c35027ca6e11