Browse Source

上传原始文件

master
Lizongdi 2 months ago
parent
commit
0b2416b8f0
  1. 127
      Bingoo/base/BHBF_ROBOT.c
  2. 636
      Bingoo/base/DLTuc.c
  3. 473
      Bingoo/base/Handset_Status_Setting.c
  4. 20
      Bingoo/base/bsp_CV.pb.c
  5. 12
      Bingoo/base/bsp_Cmd.pb.c
  6. 109
      Bingoo/base/bsp_DLT_Log.c
  7. 570
      Bingoo/base/bsp_EEPROM.c
  8. 13
      Bingoo/base/bsp_Error.pb.c
  9. 31
      Bingoo/base/bsp_Error_Detect.c
  10. 334
      Bingoo/base/bsp_FDCAN.c
  11. 104
      Bingoo/base/bsp_GPIO.c
  12. 12
      Bingoo/base/bsp_GV.pb.c
  13. 12
      Bingoo/base/bsp_IAP.pb.c
  14. 41
      Bingoo/base/bsp_INTERCALL.c
  15. 12
      Bingoo/base/bsp_IO.pb.c
  16. 12
      Bingoo/base/bsp_IV.pb.c
  17. 372
      Bingoo/base/bsp_MB_host.c
  18. 20
      Bingoo/base/bsp_PID.pb.c
  19. 12
      Bingoo/base/bsp_PV.pb.c
  20. 12
      Bingoo/base/bsp_ReCmd.pb.c
  21. 186
      Bingoo/base/bsp_TCPClient.c
  22. 71
      Bingoo/base/bsp_TIMER.c
  23. 553
      Bingoo/base/bsp_UART.c
  24. 430
      Bingoo/base/bsp_UDP.c
  25. 114
      Bingoo/base/bsp_UpperComputer_Handler.c
  26. 126
      Bingoo/base/bsp_client_setting.c
  27. 191
      Bingoo/base/bsp_com_helper.c
  28. 499
      Bingoo/base/bsp_cpu_flash.c
  29. 473
      Bingoo/base/bsp_decode_command.c
  30. 12
      Bingoo/base/bsp_ground_management.pb.c
  31. 488
      Bingoo/base/bsp_qspi_w25q128.c
  32. 58
      Bingoo/base/bsp_slide_averager.c
  33. 12
      Bingoo/base/bsp_strain_gauge.pb.c
  34. 81
      Bingoo/base/bsp_tempature.c
  35. 404
      Bingoo/base/change_line_control.c
  36. 51
      Bingoo/base/fsm_state.c
  37. 414
      Bingoo/base/fsm_state_control.c
  38. 279
      Bingoo/base/motor.c
  39. 35
      Bingoo/base/motors_power_action.c
  40. 102
      Bingoo/base/msp_DAM_Relay.c
  41. 12
      Bingoo/base/msp_MK32.pb.c
  42. 118
      Bingoo/base/msp_MK32_1.c
  43. 12
      Bingoo/base/msp_Motor.pb.c
  44. 256
      Bingoo/base/msp_PID.c
  45. 100
      Bingoo/base/msp_TL720D.c
  46. 12
      Bingoo/base/msp_TL720D.pb.c
  47. 426
      Bingoo/base/msp_TTMotor_ZQ.c
  48. 98
      Bingoo/base/msp_WH_LTE_7S0.c
  49. 20
      Bingoo/base/msp_ZQ_MotorParameters.pb.c
  50. 135
      Bingoo/base/msp_ground_management.c
  51. 137
      Bingoo/base/msp_strain_gauge.c
  52. 102
      Bingoo/base/paint_gun_action.c
  53. 388
      Bingoo/base/pb_common.c
  54. 1727
      Bingoo/base/pb_decode.c
  55. 1000
      Bingoo/base/pb_encode.c
  56. 1074
      Bingoo/base/robot_move_actions.c
  57. 100
      Bingoo/base/swing_action.c
  58. 251
      Bingoo/base/tcp_server.c
  59. 125
      Bingoo/include/base/BHBF_ROBOT.h
  60. 248
      Bingoo/include/base/DLTuc.h
  61. 74
      Bingoo/include/base/DLTucConfig.h
  62. 73
      Bingoo/include/base/Handset_Status_Setting.h
  63. 125
      Bingoo/include/base/bsp_CV.pb.h
  64. 80
      Bingoo/include/base/bsp_Cmd.pb.h
  65. 16
      Bingoo/include/base/bsp_DLT_Log.h
  66. 73
      Bingoo/include/base/bsp_EEPROM.h
  67. 78
      Bingoo/include/base/bsp_Error.pb.h
  68. 25
      Bingoo/include/base/bsp_Error_Detect.h
  69. 84
      Bingoo/include/base/bsp_FDCAN.h
  70. 18
      Bingoo/include/base/bsp_GPIO.h
  71. 167
      Bingoo/include/base/bsp_GV.pb.h
  72. 58
      Bingoo/include/base/bsp_IAP.pb.h
  73. 81
      Bingoo/include/base/bsp_IO.pb.h
  74. 147
      Bingoo/include/base/bsp_IV.pb.h
  75. 52
      Bingoo/include/base/bsp_MB_host.h
  76. 57
      Bingoo/include/base/bsp_PID.pb.h
  77. 136
      Bingoo/include/base/bsp_PV.pb.h
  78. 80
      Bingoo/include/base/bsp_ReCmd.pb.h
  79. 63
      Bingoo/include/base/bsp_TCPClient.h
  80. 17
      Bingoo/include/base/bsp_TIMER.h
  81. 109
      Bingoo/include/base/bsp_UART.h
  82. 23
      Bingoo/include/base/bsp_UDP.h
  83. 27
      Bingoo/include/base/bsp_UpperComputer_Handler.h
  84. 13
      Bingoo/include/base/bsp_client_setting.h
  85. 82
      Bingoo/include/base/bsp_com_helper.h
  86. 66
      Bingoo/include/base/bsp_cpu_flash.h
  87. 39
      Bingoo/include/base/bsp_decode_command.h
  88. 82
      Bingoo/include/base/bsp_ground_management.pb.h
  89. 57
      Bingoo/include/base/bsp_include.h
  90. 36
      Bingoo/include/base/bsp_mqtt.h
  91. 26
      Bingoo/include/base/bsp_mqtt_pub.h
  92. 51
      Bingoo/include/base/bsp_pb_decode_encode.h
  93. 107
      Bingoo/include/base/bsp_qspi_w25q128.h
  94. 14
      Bingoo/include/base/bsp_slide_averager.h
  95. 61
      Bingoo/include/base/bsp_strain_gauge.pb.h
  96. 19
      Bingoo/include/base/bsp_tempature.h
  97. 56
      Bingoo/include/base/change_line_control.h
  98. 44
      Bingoo/include/base/fsm_state.h
  99. 18
      Bingoo/include/base/fsm_state_control.h
  100. 21
      Bingoo/include/base/motor.h

127
Bingoo/base/BHBF_ROBOT.c

@ -0,0 +1,127 @@
/*
* BHBF_ROBOT.c
*
* Created on: Oct 26, 2023
* Author: shiya
*/
#include "fsm.h"
#include "BHBF_ROBOT.h"
#include <string.h>
#include "bsp_FDCAN.h"
int32_t* SystemTimeMiliSeconds; //似乎未用
int32_t SystemTimeMiliCount; //2ms加一
int32_t* SystemErrorCode;
ErrorData* SystemErrorData;
//Declare a CV and initialize CV
CV_struct_define CV =
{ 0 };
//Declare a GV and initialize CV
GV_struct_define GV =
{ 0 };
PV_struct_define decoded_PV_variable = { 0 };
PV_struct_define decoded_PV = { 0 };
IV_struct_define IV ={ 0 };
void SET_BIT_1(int32_t* num,int32_t k)
{
*num=((*num) | (1 << (k)));
}
void SET_BIT_0(int32_t* num,int32_t k)
{
*num=((*num) & ~(1 << (k)));
}
int32_t Get_BIT(int32_t* num,int32_t k)
{
return (*num >> (k)) & 1;
}
void SystemTimer_Intialize()
{
SystemTimeMiliCount=0;
GF_BSP_Interrupt_Add_CallBack(
DF_BSP_InterCall_TIM8_2ms_PeriodElapsedCallback, GF_Timer_Count);
}
void GF_Timer_Count()
{
SystemTimeMiliCount++;
}
Sys_timer_handler timer_handler_1;
Sys_timer_handler timer_handler_2;
Sys_timer_handler timer_handler_3;
Sys_timer_handler timer_handler_4;
int sys_timer_1_flag_count[4];
bool CompareTimer(int32_t DelayMiliSeconds,Sys_timer_handler * timer_handler)
{
if(timer_handler->start_timer==1)
{
timer_handler->sys_current_timer_count=DelayMiliSeconds/2+SystemTimeMiliCount;
timer_handler->start_timer=0;
}
if(timer_handler->sys_current_timer_count<=SystemTimeMiliCount)
{
return true;
}else
{
return false;
}
}
bool CompareTimer_Delay(int32_t Delay)
{
int32_t tickstart = SystemTimeMiliCount;
int32_t wait = Delay;
/* Add a freq to guarantee minimum wait */
if (wait < HAL_MAX_DELAY)
{
int32_t wait = Delay;
while ((SystemTimeMiliCount - tickstart) < wait/2)
{
}
}
}
/*m/min--->0.1m/min 其实就是×10*/
int32_t speed_M_min_toE01_M_min(int32_t speedm_min)
{
return speedm_min*10;
}

636
Bingoo/base/DLTuc.c

@ -0,0 +1,636 @@
/**
* @file DLTuc.c
* @author Teodor Rosolowski
* @date 1 Jul 2022
* @brief This file is a part of DLTuc library
*
* In this source file you will find entire implementation of the DLTuc lib.
*
* Requirments:
* Around ~2kB of RAM
* Check Configuration file and defines:
* DLT_TRANSMIT_RING_BUFFER_SIZE, DLT_TRANSMIT_MAX_SINGLE_MESSAGE_SIZE
*
*/
/*
* *******************************************************************************************
* Includes
* *******************************************************************************************
* */
#include "DLTuc.h"
#include "stdio.h"
#include "stdint.h"
#include "stdbool.h"
#include <stdarg.h>
#include <string.h>
/*
* *******************************************************************************************
* Local defines
* *******************************************************************************************
* */
/**!
* \brief DLT_ACT_HEADER_SIZE - actual DLT header size
* \details Standard Header + Extended + TypeInfo
* Don't modify it if you aren't sure what are you doing!!!
*/
#define DLT_ACT_HEADER_SIZE 32
/**!
* \brief DLT_MINIMUM_LOG_DROP_PERIOD
* \details minimum period between two drop info log
*/
#define DLT_MINIMUM_LOG_DROP_PERIOD 200
/*
* *******************************************************************************************
* Local types
* *******************************************************************************************
* */
/* Prototypes to improve readability.. */
/*typedefs for future use..*/
// typedef
// {
// uint32_t HeaderStart;
// BaseHeaderConfig_t BaseHeaderConfig;
// uint8_t MessageCounter;
// uint16_t MessageLength;
// uint32_t EcuId;
// uint32_t TimeStamp;
// }DLT_BaseHeader_t;
// typedef
// {
// DLT_DebugLevel_t DebugLevel;
// uint8_t NumberOfArguments;
// uint32_t AppId;
// uint32_t ContexID;
// TypeInfo_t TypeInfo;
// uint16_t Argument1;
// }DLT_ExtendedHeader_t;
//char DLT_LOG_ENABLE_LEVEL= 7;
char DLT_LOG_ENABLE_LEVEL= 0;
/**!
* \brief RB_Status
* \details ---
* */
typedef enum
{
RB_OK = 0,
RB_ERROR = 1
} RB_Status;
/**!
* \brief DltRingBufferTransmit_t
* \details ---
* */
typedef struct DltRingBufferTransmit_Tag
{
uint16_t Head; // Pointer to write
uint16_t Tail; // Pointer to read
bool readyToTransmit[DLT_TRANSMIT_RING_BUFFER_SIZE];
uint8_t dataSize[DLT_TRANSMIT_RING_BUFFER_SIZE]; // Array to keep message size
} DltRingBufferTransmit_t;
/**!
* \brief BluRingBufferReceive_t
* \details ---
* */
typedef struct BluRingBufferReceive_Tag
{
uint16_t Head; // Pointer to write
uint16_t Tail; // Pointer to read
uint8_t MessageSize[DLT_RECEIVE_RING_BUFFER_SIZE]; // Array to keep message size
bool ReadyToRead[DLT_RECEIVE_RING_BUFFER_SIZE];
} BluRingBufferReceive_t;
/**
* *******************************************************************************************
* Static variables
* *******************************************************************************************
* */
/**!
* \brief ExtSerialTrDataFunctionCb
* \details ---
* */
static void (*ExtSerialTrDataFunctionCb)(uint8_t *DltLogData, uint8_t Size);
static void (*ExtSerialRecDataFunctionCb)(uint8_t *RecDataBuff, uint16_t Size);
static void (*ExtInfoInjectionDataRcvdCb)(uint32_t AppId, uint32_t ConId,uint32_t ServId,uint8_t *Data, uint16_t Size);
static uint32_t (*GetSystemTimeMs)(void);
/**!
* \brief LogDroppedFlag
* \details ---
* */
static bool LogDroppedFlag =false;
static uint32_t PrevLogDropSendTime = 0u;
static uint8_t DltLogDroppedInfo[] = "LOG DROPPED!!!";
static uint8_t DltLogDroppedInfoBuffer[60] = {0}; /* TODO: Remove magic number..*/
static uint8_t DLtLogDroppedSize = 0;
static uint8_t ActDltMessageCounter =0;
static DltRingBufferTransmit_t DltTrsmtRingBuffer = {.readyToTransmit[0]=true};
static uint8_t DltTrsmtMessagesTab[DLT_TRANSMIT_RING_BUFFER_SIZE][DLT_TRANSMIT_MAX_SINGLE_MESSAGE_SIZE];
static BluRingBufferReceive_t BleMainReceiveRingBuffer;
static uint8_t BluMainReceiveMessagesTab[DLT_RECEIVE_RING_BUFFER_SIZE][DLT_REC_SINGLE_MESSAGE_MAX_SIZE];
static volatile uint8_t TransmitReadyStateFlag = true; /*TmpFromDma for example*/
/*
*********************************************************************************************
* Prototypes of static functions
********************************************************************************************
*/
/*!
************************************************************************************************
* \brief PrepareDltHeader
* \details A very lazy implementation of DLT Header - but it works fine
* Please refer to: https://www.autosar.org/fileadmin/user_upload/standards/foundation/1-0/AUTOSAR_PRS_DiagnosticLogAndTraceProtocol.pdf
************************************************************************************************/
static void PrepareDltHeader(uint8_t Level, uint32_t AppId, uint32_t ContextId, uint16_t size,uint8_t *headerAddrStart);
/*!
************************************************************************************************
* \brief DLT_RB_TransmitRead Function to read data from ring buffer
* \details --
* \param RingBuffer_t *Buf - pointer to Ring Buffer structure
* \param out MessageSize - size of the "DltLogData" (return value)
* \param out MessagePointer - pointer to the message stored in RingBuffer (return value)
* \return RB_OK if something read succesfully, otherwise RB_ERROR
* */
static RB_Status DLT_RB_TransmitRead(DltRingBufferTransmit_t *Buf, uint8_t *MessageSize, uint8_t **MessagePointer);
/*!
************************************************************************************************
* \brief DLT_RB_GetNextWriteIndex
* \details --
* \param in RingBuffer_t *Buf - pointer to Ring Buffer structure
* \param out writeIndex - next index where DLT data should be stored, can be used only if fun return "RB_OK"
* \return RB_OK if index available, otherwise RB_ERROR
************************************************************************************************/
static RB_Status DLT_RB_GetNextWriteIndex(DltRingBufferTransmit_t *Buf,uint16_t *writeIndex);
/*!
************************************************************************************************
* \brief DLT_RB_Receive_GetNextMessageAddress
* \details Function used to work with DMA - direct write to ring buffer by DMA
* \param in Buf -
* \param in WriteAddress -
************************************************************************************************/
static RB_Status DLT_RB_Receive_GetNextMessageAddress(BluRingBufferReceive_t *Buf, uint8_t **WriteAddress);
/*!
************************************************************************************************
* \brief DLT_RB_Receive_Read Function to read data from ring buffer
* \details --
* \param RingBuffer_t *Buf - pointer to Ring Buffer structure
* \param out MessageSize - size of the "BleLogData" (return value)
* \param out MessagePointer - pointer to the message stored in RingBuffer (return value)
*
* */
static RB_Status DLT_RB_Receive_Read(BluRingBufferReceive_t *Buf, uint8_t *MessageSize, uint8_t **MessagePointer);
/*
*********************************************************************************************
* Static functions implementation
********************************************************************************************
*/
static RB_Status DLT_RB_Receive_GetNextMessageAddress(BluRingBufferReceive_t *Buf, uint8_t **WriteAddress)
{
/* TODO: The implementation isn't optimal...*/
static uint8_t DefaultBlindBuffer[DLT_REC_SINGLE_MESSAGE_MAX_SIZE];
/*Mark previous message as ready to read*/
Buf->ReadyToRead[Buf->Head] = true;
// Compute new Head pointer value of a ring buffer
uint16_t HeadTmp = (Buf->Head + 1) % DLT_RECEIVE_RING_BUFFER_SIZE;
// Check if there is one free space ahead the Head buffer
if(HeadTmp == Buf->Tail)
{
/*Even if buffer is full data must be received somewhere to don't crush application/ dma*/
*WriteAddress = DefaultBlindBuffer;
// There is no space in the buffer - return an error
return RB_ERROR;
}
Buf->ReadyToRead[HeadTmp] = false;
Buf->MessageSize[HeadTmp] = DLT_RECEIVE_RING_BUFFER_SIZE;
Buf->Head = HeadTmp;
*WriteAddress = &BluMainReceiveMessagesTab[HeadTmp][0];
// Everything is ok - return OK status
return RB_OK;
}
static RB_Status DLT_RB_Receive_Read(BluRingBufferReceive_t *Buf, uint8_t *MessageSize, uint8_t **MessagePointer)
{
if(Buf->ReadyToRead[Buf->Tail] == false)
{
/*Any message in ring buffer isn't ready to read*/
return RB_ERROR;
}
/*Mark again as not ready to read*/
Buf->ReadyToRead[Buf->Tail] = false;
// Check if Tail hit Head
if(Buf->Head == Buf->Tail)
{
// If yes - there is nothing to read
return RB_ERROR;
}
// Write current value from buffer to pointer from argument
*MessageSize = Buf->MessageSize[Buf->Tail];
*MessagePointer = &BluMainReceiveMessagesTab[Buf->Tail][0];
// Calculate new Tail pointer
Buf->Tail = (Buf->Tail + 1) % DLT_RECEIVE_RING_BUFFER_SIZE;
// Everything is ok - return OK status
return RB_OK;
}
static RB_Status DLT_RB_TransmitRead(DltRingBufferTransmit_t *Buf, uint8_t *MessageSize, uint8_t **MessagePointer)
{
// Check if Tail hit Head
if(Buf->Head == Buf->Tail)
{
// If yes - there is nothing to read
return RB_ERROR;
}
else if(true == Buf->readyToTransmit[Buf->Tail])
{
// Write current value from buffer to pointer from argument
*MessageSize = Buf->dataSize[Buf->Tail];
*MessagePointer = &DltTrsmtMessagesTab[Buf->Tail][0];
// Calculate new Tail pointer
Buf->Tail = (Buf->Tail + 1) % DLT_TRANSMIT_RING_BUFFER_SIZE;
// Everything is ok - return OK status
return RB_OK;
}
else
{
/* Message still not ready to transmit */
return RB_ERROR;
}
}
static RB_Status DLT_RB_GetNextWriteIndex(DltRingBufferTransmit_t *Buf,uint16_t *writeIndex)
{
DLTuc_OS_CRITICAL_START();
// Calculate new Head pointer value
uint8_t HeadTmp = (Buf->Head + 1) % DLT_TRANSMIT_RING_BUFFER_SIZE;
// Check if there is one free space ahead the Head buffer
if(HeadTmp == Buf->Tail)
{
DLTuc_OS_CRITICAL_END();
// There is no space in the buffer - return an error
return RB_ERROR;
}
Buf->Head = HeadTmp;
Buf->readyToTransmit[Buf->Head] = false;
*writeIndex = Buf->Head;
DLTuc_OS_CRITICAL_END();
return RB_OK;
}
static void PrepareDltHeader(uint8_t Level, uint32_t AppId, uint32_t ContextId, uint16_t size,uint8_t *headerAddrStart)
{
uint32_t ActualTime = 0;
if(GetSystemTimeMs != NULL)
{
ActualTime = GetSystemTimeMs() * 10U;
/*Multiply by 10 to get value in MS also in DLTViewer
*Reson: Resolution in DLT Viewer is equal: 10^-4
*/
}
if(size > ((UINT8_MAX -1) - DLT_ACT_HEADER_SIZE) )
{
/*Error to handle, or please develop this function to handle input size > UINT8_MAX */
// while(1)
// {
// /*For development phase: lock the app*/
// }
size = size - DLT_ACT_HEADER_SIZE -1;
}
/*START HEADER*/
headerAddrStart[0] = 0x44; /*'D'*/
headerAddrStart[1] = 0x4c; /*'L'*/
headerAddrStart[2] = 0x53; /*'S'*/
headerAddrStart[3] = 0x01; /*'0x01'*/
headerAddrStart[4] = 0x35; /*'Dlt base header config
* Use extended header - true
* MSBF - false
* With ECU ID - true
* With Seesion ID - false
* With time stamp - true
* version number -random
'*/
headerAddrStart[5] = ActDltMessageCounter++; /*'Message counter value '*/
/*TODO: - it must be fixed!!!! - Length*/
headerAddrStart[6] = 0x00; /*Message length general*/
// headerAddrStart[7] = 0x37; /*'Message length general '*/
headerAddrStart[7]=28+size; /*General size */
uint32_t TempEcuId = DLT_LOG_ECUID_VALUE;
/*ECU ID*/
headerAddrStart[8]= ((uint8_t*)&TempEcuId)[3];
headerAddrStart[9]= ((uint8_t*)&TempEcuId)[2];
headerAddrStart[10]= ((uint8_t*)&TempEcuId)[1];
headerAddrStart[11]= ((uint8_t*)&TempEcuId)[0];
/*Time stamp*/
headerAddrStart[12]= ((uint8_t*)&ActualTime)[3];
headerAddrStart[13]= ((uint8_t*)&ActualTime)[2];
headerAddrStart[14]= ((uint8_t*)&ActualTime)[1];
headerAddrStart[15]= ((uint8_t*)&ActualTime)[0];
/*Extended header --verbose | type serial*/
// headerAddrStart[16]= 0x41; /**/
headerAddrStart[16]= (Level << 4) | 1;
/*Number of arguments*/
headerAddrStart[17]= 0x01; /**/
/*App id */
headerAddrStart[18]= ((uint8_t*)&AppId)[3];
headerAddrStart[19]= ((uint8_t*)&AppId)[2];
headerAddrStart[20]= ((uint8_t*)&AppId)[1];
headerAddrStart[21]= ((uint8_t*)&AppId)[0];
/*Contex ID (4 bytes*/
headerAddrStart[22]= ((uint8_t*)&ContextId)[3];
headerAddrStart[23]= ((uint8_t*)&ContextId)[2];
headerAddrStart[24]= ((uint8_t*)&ContextId)[1];
headerAddrStart[25]= ((uint8_t*)&ContextId)[0];
/*Type info*/
headerAddrStart[26]= 0x01; /**/
headerAddrStart[27]= 0x82; /**/
headerAddrStart[28]= 0x00; /**/
headerAddrStart[29]= 0x00; /**/
/*Argument 1*/
headerAddrStart[30]= size;
/* Size of the load in simplified form, please verify in documentation of DLT protcool documentation */
headerAddrStart[31]= 0x00; /**/
}
/*
****************************************************************************************************
* Exported functions implementation.
* Descriptions are added in header file
*****************************************************************************************************
*/
void DLTuc_RawDataReceiveDone(uint16_t Size)
{
static uint8_t *MessageReceiveBufferAddress = NULL;
uint8_t *MessageToRead_p = NULL;
uint8_t MessageToReadSize= 0U;
DLT_RB_Receive_GetNextMessageAddress(&BleMainReceiveRingBuffer,&MessageReceiveBufferAddress);
if(ExtSerialRecDataFunctionCb != NULL){
ExtSerialRecDataFunctionCb(MessageReceiveBufferAddress,DLT_REC_SINGLE_MESSAGE_MAX_SIZE);
}
/*
* The receive buffer isn't handled fully correctly, it require deeper investigation.
* However, it is possible to receive the Injection messages, and base commands if are transmitted with breakes..
* Received DTL messages are divided by the "IDLE" irq for now.., not by the size and etc...
*/
if(DLT_RB_Receive_Read(&BleMainReceiveRingBuffer, &MessageToReadSize,&MessageToRead_p) == RB_OK)
{
if(MessageToRead_p[4] == 53) /**/
{
/*Use Extended, with EcuId, with Timestamp, end at[15]
then Extended data as follow:
[16] ==22-? - non verbose, type: control, MSTP: fatal
[17] numOfArgs == 1 - TODO: Only 1 argument is for nowsupported!!!
[18-21] - AppId
[22-25] - ContexId
[26-29] - ServiceId
[30-33] - Size*/
uint32_t AppId = MessageToRead_p[21] << 24 |MessageToRead_p[20] << 16 | MessageToRead_p[19] << 8 | MessageToRead_p[18] << 0;
uint32_t RecContexId = MessageToRead_p[25] << 24 |MessageToRead_p[24] << 16 | MessageToRead_p[23] << 8 | MessageToRead_p[22] << 0;
uint32_t RecServiceId = MessageToRead_p[29] << 24 |MessageToRead_p[28] << 16 | MessageToRead_p[27] << 8 | MessageToRead_p[26] << 0;
if(RecServiceId >= DLT_SERVICE_ID_CALLSW_CINJECTION)
{
if(NULL != ExtInfoInjectionDataRcvdCb)
{
/*MSB LSB, wtf..?, it is somehow mixed? */
uint32_t DltDatSize = MessageToRead_p[33] << 24 | MessageToRead_p[32] << 16 | MessageToRead_p[31] << 8 | MessageToRead_p[30] << 0;
ExtInfoInjectionDataRcvdCb(AppId,RecContexId,RecServiceId,&MessageToRead_p[34],(uint16_t)DltDatSize);
}
}
else if(RecServiceId == DLT_SERVICE_ID_SET_LOG_LEVEL)
{
uint32_t NewLogLevel = MessageToRead_p[30];
LOG("Set new log level request: %d How you triggered it?? , not supported", NewLogLevel);
/* It is handled correctly by DLT Viewer?? */
}
else if(RecServiceId == DLT_SERVICE_ID_SET_DEFAULT_LOG_LEVEL)
{
uint32_t NewLogLevel = MessageToRead_p[30];
LOG("Set default log level request: %d", NewLogLevel);
LOG("Not supported yet, I'm too lazy :)");
}
else if(DLT_SERVICE_ID_GET_SOFTWARE_VERSION == RecServiceId)
{
LOG("ECU_SW_VERSION: %d", DLT_ECU_SW_VER);
/*TODO: The lib should send here answer of control message... */
}
else if(DLT_SERVICE_ID_GET_DEFAULT_LOG_LEVEL == RecServiceId)
{
LOG("Default log level: %d", DLT_LOG_ENABLE_LEVEL);
}
}
}
}
void DLTuc_RegisterInjectionDataReceivedCb(
void InjectionDataRcvd(uint32_t AppId, uint32_t ConId,uint32_t ServId,uint8_t *Data, uint16_t Size))
{
ExtInfoInjectionDataRcvdCb = InjectionDataRcvd;
}
void DLTuc_RegisterReceiveSerialDataFunction(void LLSerialRecDataFunctionC(uint8_t *DltLogData, uint16_t Size))
{
ExtSerialRecDataFunctionCb = LLSerialRecDataFunctionC;
if(ExtSerialRecDataFunctionCb != NULL)
{
ExtSerialRecDataFunctionCb(&BluMainReceiveMessagesTab[0][0],DLT_REC_SINGLE_MESSAGE_MAX_SIZE);
}
}
void DLTuc_RegisterTransmitSerialDataFunction(void LLSerialTrDataFunctionC(uint8_t *DltLogData, uint8_t Size))
{
ExtSerialTrDataFunctionCb = LLSerialTrDataFunctionC;
/*Preapre LOG DROP Info Log*/
/* 0x444C5443 - In Ascii code it is: DLTC. It is more convience to put magic numbers here :) */
PrepareDltHeader(DL_ERROR,0x444C5443, 0x444C5443,sizeof(DltLogDroppedInfo),DltLogDroppedInfoBuffer);
for(int i=0; i<sizeof(DltLogDroppedInfo); i++)
{
DltLogDroppedInfoBuffer[i+DLT_ACT_HEADER_SIZE] = DltLogDroppedInfo[i];
}
DLtLogDroppedSize = DLT_ACT_HEADER_SIZE + sizeof(DltLogDroppedInfo);
}
void DLTuc_MessageTransmitDone(void)
{
uint8_t TmpMessageSize=0;
uint8_t *TmpMessagePointer = NULL;
uint32_t ActualSysTime = 0u;
if(GetSystemTimeMs != NULL)
{
ActualSysTime = GetSystemTimeMs();
}
if(LogDroppedFlag == true && (ActualSysTime - PrevLogDropSendTime > DLT_MINIMUM_LOG_DROP_PERIOD) )
{
/* If DLTuc will always send the DROP Message info,
* then will not read any message from RB..*/
PrevLogDropSendTime = ActualSysTime;
LogDroppedFlag = false;
if(ExtSerialTrDataFunctionCb != NULL)
{
ExtSerialTrDataFunctionCb(DltLogDroppedInfoBuffer, DLtLogDroppedSize);
}
return;
}
DLTuc_OS_CRITICAL_START();
if(DLT_RB_TransmitRead(&DltTrsmtRingBuffer,&TmpMessageSize,&TmpMessagePointer) == RB_OK)
{
if(ExtSerialTrDataFunctionCb != NULL)
{
DLTuc_OS_CRITICAL_END();
ExtSerialTrDataFunctionCb(TmpMessagePointer, TmpMessageSize);
}
}
else
{
TransmitReadyStateFlag = true;
}
DLTuc_OS_CRITICAL_END();
}
void DLTuc_LogOutVarArgs(DltLogLevel_t Level, uint32_t AppId, uint32_t ContextId, uint8_t *Payload, ...)
{
uint16_t Size; /* */
uint8_t TmpMessageSize=0U; /* */
uint8_t *TmpMessagePointer = NULL; /* */
uint16_t writeIndex = 0U; /* */
if(DLT_RB_GetNextWriteIndex(&DltTrsmtRingBuffer,&writeIndex) != RB_OK)
{
DLTuc_OS_CRITICAL_START();
LogDroppedFlag = true;
DLTuc_OS_CRITICAL_END();
}
else
{
/* Put the DLT message data directly in ring buffer*/
va_list ap; /* */
va_start(ap, Payload);
Size = vsprintf((char *)&(DltTrsmtMessagesTab[writeIndex][DLT_ACT_HEADER_SIZE]), (char *)Payload,ap);
va_end(ap);
Size += DLT_ACT_HEADER_SIZE;
/*Add additional zeros on the end of message - thanks to that it work stable */
Size++;
DltTrsmtMessagesTab[writeIndex][Size] = 0U;
Size++;
DltTrsmtMessagesTab[writeIndex][Size] = 0U;
PrepareDltHeader(Level,AppId,ContextId,Size,&(DltTrsmtMessagesTab[writeIndex][0]));
Size = Size + DLT_ACT_HEADER_SIZE;
DltTrsmtRingBuffer.dataSize[writeIndex] = Size;
DLTuc_OS_CRITICAL_START();
DltTrsmtRingBuffer.readyToTransmit[writeIndex] = true;
DLTuc_OS_CRITICAL_END();
}
DLTuc_OS_CRITICAL_START();
if(TransmitReadyStateFlag == true)
{
if(DLT_RB_TransmitRead(&DltTrsmtRingBuffer,&TmpMessageSize,&TmpMessagePointer) == RB_OK)
{
if(TmpMessageSize != 0U)
{
TransmitReadyStateFlag = false;
DLTuc_OS_CRITICAL_END();
/*Log transmission must be started in this contex...*/
/***********************************************/
/* It may be a bug in implementation - it must be investigated.. */
/* It's important to be aware of this fact!!*/
/***********************************************/
if(ExtSerialTrDataFunctionCb != NULL)
{
ExtSerialTrDataFunctionCb(TmpMessagePointer, TmpMessageSize);
}
else
{
// while(1); /*Please Register the callback...*/
}
}
}
}
DLTuc_OS_CRITICAL_END();
}
void DLTuc_RegisterGetTimeStampMsCallback(uint32_t GetSysTime(void))
{
GetSystemTimeMs = GetSysTime;
}

473
Bingoo/base/Handset_Status_Setting.c

@ -0,0 +1,473 @@
/*
* @file Handset_Status_Setting.c
* @brief /
* @author bm673
* @date 2026115
* @details IO状态获取姿
*/
#include "Handset_Status_Setting.h"
#include "BHBF_ROBOT.h"
#include <math.h>
/*=========================== 宏定义配置 ===========================*/
// 摇杆阈值配置
#define ROCKER_THRESHOLD_DEFAULT 300U // 摇杆死区阈值
#define ANGLE_DEAD_ZONE 20U // 角度死区(度)
// 机器人运动角度判断阈值
#define ANGLE_FORWARD_LEFT_MIN 70
#define ANGLE_FORWARD_LEFT_MAX 110
#define ANGLE_FORWARD_RIGHT_MIN -110
#define ANGLE_FORWARD_RIGHT_MAX -70
#define ANGLE_REVERSE_MIN 160
// 摇杆方向角度区间定义
#define ANGLE_FORWARD_LIMIT1 70
#define ANGLE_FORWARD_LIMIT2 110
#define ANGLE_LEFT_LIMIT1 160
#define ANGLE_LEFT_LIMIT2 -160
#define ANGLE_RIGHT_LIMIT1 -20
#define ANGLE_RIGHT_LIMIT2 20
#define ANGLE_BACK_LIMIT1 -70
#define ANGLE_BACK_LIMIT2 -110
// 姿态补偿参数配置
#define COMP_DEADZONE 300 // 遥控器补偿生效阈值
#define COMP_COUNT_THRESH 200 // 补偿计数阈值(400ms累加一次)
#define COMP_STEP 10 // 补偿步长
#define COMP_LIMIT_MAX 1000 // 正向补偿最大值
#define COMP_LIMIT_MIN -1000 // 负向补偿最大值
/*=========================== 静态函数声明 ===========================*/
typedef InputEvent (*ModeEventHandler)(void);
// 急停检测
static inline InputEvent CheckEmergencyStop(void);
// 各模式事件处理函数
static InputEvent GetHaltModeEvents(void);
static InputEvent GetManualModeEvents(void);
static InputEvent GetHorizontalModeEvents(void);
static InputEvent GetFlatModeEvents(void);
static InputEvent GetVerticalLeftModeEvents(void);
static InputEvent GetVerticalRightModeEvents(void);
static InputEvent GetRegionalFlatTaskEvents(void);
static InputEvent GetRegionalHorizontalTaskEvents(void);
// 辅助功能函数
static InputEvent CheckCommonKeys(void);
static InputEvent CheckCommonKeys_to_manual(void);
static InputEvent CheckAllKeys(void);
static InputEvent CalculateRockerEvent(void);
static InputEvent CalculateRockerEvent_manual(void);
static void Update_Single_Compensation(int32_t chVal, float* pComp, int* pCnt);
/*=========================== 全局变量 ===========================*/
extern float left_compare_value;
extern float right_compare_value;
// 模式-事件处理函数映射表
static const ModeEventHandler modeEventHandlers[MODE_COUNT] = {
[Halt_Mode] = GetHaltModeEvents,
[Manual_Mode] = GetManualModeEvents,
[Horizontal_Mode] = GetHorizontalModeEvents,
[Flat_Mode] = GetFlatModeEvents,
[Vertical_Mode_Left] = GetVerticalLeftModeEvents,
[Vertical_Mode_Right] = GetVerticalRightModeEvents,
[Regional_Horizontal_Automatic_Task] = GetRegionalHorizontalTaskEvents,
[Regional_Flat_Automatic_Task] = GetRegionalFlatTaskEvents,
};
/*=========================== 函数实现 ===========================*/
/**
* @brief
* @param
* @return Robot_Mode
*/
Robot_Mode RobotRockerState(void)
{
if (GV.PV.Robot_Operation_Mode <= 0 || GV.PV.Robot_Operation_Mode >= MODE_COUNT)
{
return Halt_Mode;
}
switch (GV.PV.Robot_Operation_Mode)
{
case 0: return Halt_Mode;
case 1: return Manual_Mode;
case 2: return Horizontal_Mode;
case 3: return Flat_Mode;
case 4: return Vertical_Mode_Left;
case 5: return Vertical_Mode_Right;
case 6: return Regional_Horizontal_Automatic_Task;
case 7: return Regional_Flat_Automatic_Task;
default: return Halt_Mode;
}
}
/**
* @brief /
* @param current_mode
* @return InputEvent
*/
InputEvent RemoteControl_GetKeyIndex(Robot_Mode current_mode)
{
// 安全校验
if (current_mode < 0 || current_mode >= MODE_COUNT)
{
return INPUT_NONE;
}
// 获取对应模式的事件处理函数并执行
ModeEventHandler handler = modeEventHandlers[current_mode];
return (handler != NULL) ? handler() : INPUT_NONE;
}
/**
* @brief //
* @param
* @return InputEvent
*/
static inline InputEvent CheckCommonKeys(void)
{
if (P_MK32->CH7_SD == -1000) return INPUT_KEY_AUTO_WORK_UP;
if (P_MK32->CH4_SA == -1000) return INPUT_KEY_LANE_CHANGE_UP;
if (P_MK32->CH5_SB == -1000) return INPUT_KEY_FORWARD_CRUISE;
if (P_MK32->CH5_SB == 1000) return INPUT_KEY_BACKWARD_CRUISE;
return INPUT_NONE;
}
/**
* @brief //
* @param
* @return InputEvent
*/
static inline InputEvent CheckCommonKeys_to_manual(void)
{
if (P_MK32->CH7_SD == -1000) return INPUT_KEY_AUTO_WORK_UP;
if (P_MK32->CH5_SB == -1000) return INPUT_KEY_FORWARD_CRUISE;
if (P_MK32->CH5_SB == 1000) return INPUT_KEY_BACKWARD_CRUISE;
return INPUT_NONE;
}
/**
* @brief
* @param
* @return InputEvent
*/
static inline InputEvent CheckAllKeys(void)
{
if (P_MK32->CH7_SD == -1000) return INPUT_KEY_AUTO_WORK_UP;
if (P_MK32->CH7_SD == 1000) return INPUT_KEY_AUTO_WORK_DOWN;
if (P_MK32->CH4_SA == -1000) return INPUT_KEY_LANE_CHANGE_UP;
if (P_MK32->CH4_SA == 1000) return INPUT_KEY_LANE_CHANGE_DOWN;
if (P_MK32->CH5_SB == -1000) return INPUT_KEY_FORWARD_CRUISE;
if (P_MK32->CH5_SB == 1000) return INPUT_KEY_BACKWARD_CRUISE;
return INPUT_NONE;
}
/**
* @brief
* @param
* @return InputEvent
*/
static InputEvent CalculateRockerEvent(void)
{
int16_t vert = P_MK32->CH2_LY_V;
int16_t hori = P_MK32->CH3_LY_H;
int16_t swing = P_MK32->CH0_RY_H;
// 摇杆中位判断
if ((fabs(vert) < ROCKER_THRESHOLD_DEFAULT) && (fabs(hori) < ROCKER_THRESHOLD_DEFAULT))
{
return INPUT_ROCKER_STOP;
}
// 角度计算
double angle_rad = atan2(vert, hori);
int16_t angle_deg = (int16_t)(angle_rad * 180.0 / M_PI);
// 方向判断
if (angle_deg <= ANGLE_FORWARD_LIMIT2 && angle_deg >= ANGLE_FORWARD_LIMIT1)
{
return INPUT_ROCKER_FORWARD;
}
if (angle_deg >= ANGLE_LEFT_LIMIT1 || angle_deg <= ANGLE_LEFT_LIMIT2)
{
return INPUT_ROCKER_TURN_LEFT;
}
if (angle_deg >= ANGLE_RIGHT_LIMIT1 && angle_deg <= ANGLE_RIGHT_LIMIT2)
{
return INPUT_ROCKER_TURN_RIGHT;
}
if (angle_deg >= ANGLE_BACK_LIMIT2 && angle_deg <= ANGLE_BACK_LIMIT1)
{
return INPUT_ROCKER_BACKWARD;
}
return INPUT_ROCKER_STOP;
}
/**
* @brief
* @param
* @return InputEvent
*/
static InputEvent CalculateRockerEvent_manual(void)
{
int16_t vert = P_MK32->CH2_LY_V;
int16_t hori = P_MK32->CH3_LY_H;
// 摇杆中位判断
if ((fabs(vert) < ROCKER_THRESHOLD_DEFAULT) && (fabs(hori) < ROCKER_THRESHOLD_DEFAULT))
{
if (P_MK32->CH4_SA == -1000)
{
return INPUT_KEY_LANE_CHANGE_UP;
}
return INPUT_ROCKER_STOP;
}
// 角度计算
double angle_rad = atan2(vert, hori);
int16_t angle_deg = (int16_t)(angle_rad * 180.0 / M_PI);
// 方向判断
if (angle_deg <= ANGLE_FORWARD_LIMIT2 && angle_deg >= ANGLE_FORWARD_LIMIT1)
{
return INPUT_ROCKER_FORWARD;
}
if (angle_deg >= ANGLE_LEFT_LIMIT1 || angle_deg <= ANGLE_LEFT_LIMIT2)
{
return INPUT_ROCKER_TURN_LEFT;
}
if (angle_deg >= ANGLE_RIGHT_LIMIT1 && angle_deg <= ANGLE_RIGHT_LIMIT2)
{
return INPUT_ROCKER_TURN_RIGHT;
}
if (angle_deg >= ANGLE_BACK_LIMIT2 && angle_deg <= ANGLE_BACK_LIMIT1)
{
return INPUT_ROCKER_BACKWARD;
}
return INPUT_ROCKER_STOP;
}
/**
* @brief
* @param
* @return InputEvent /
*/
static inline InputEvent CheckEmergencyStop(void)
{
if (P_MK32->CH8_SE == -1000 && P_MK32->CH9_SF == -1000)
{
return EMERGENCE_STOP;
}
return INPUT_NONE;
}
/*-------------------------- 各模式事件处理函数 --------------------------*/
static InputEvent GetHaltModeEvents(void)
{
InputEvent key = CheckEmergencyStop();
if (key != INPUT_NONE) return key;
key = CheckAllKeys();
return (key != INPUT_NONE) ? key : CalculateRockerEvent();
}
static InputEvent GetManualModeEvents(void)
{
InputEvent key = CheckEmergencyStop();
if (key != INPUT_NONE) return key;
key = CheckCommonKeys_to_manual();
return (key != INPUT_NONE) ? key : CalculateRockerEvent_manual();
}
static InputEvent GetHorizontalModeEvents(void)
{
InputEvent key = CheckEmergencyStop();
if (key != INPUT_NONE) return key;
key = CheckCommonKeys();
return (key != INPUT_NONE) ? key : CalculateRockerEvent();
}
static InputEvent GetFlatModeEvents(void)
{
InputEvent key = CheckEmergencyStop();
if (key != INPUT_NONE) return key;
key = CheckCommonKeys();
return (key != INPUT_NONE) ? key : CalculateRockerEvent();
}
static InputEvent GetVerticalLeftModeEvents(void)
{
InputEvent key = CheckEmergencyStop();
if (key != INPUT_NONE) return key;
key = CheckCommonKeys();
return (key != INPUT_NONE) ? key : CalculateRockerEvent();
}
static InputEvent GetVerticalRightModeEvents(void)
{
InputEvent key = CheckEmergencyStop();
if (key != INPUT_NONE) return key;
key = CheckCommonKeys();
return (key != INPUT_NONE) ? key : CalculateRockerEvent();
}
static InputEvent GetRegionalHorizontalTaskEvents(void)
{
InputEvent key = CheckEmergencyStop();
if (key != INPUT_NONE) return key;
if (P_MK32->CH7_SD == -1000) return INPUT_KEY_AUTO_WORK_UP;
return CalculateRockerEvent();
}
static InputEvent GetRegionalFlatTaskEvents(void)
{
InputEvent key = CheckEmergencyStop();
if (key != INPUT_NONE) return key;
if (P_MK32->CH7_SD == -1000) return INPUT_KEY_AUTO_WORK_UP;
return CalculateRockerEvent();
}
/**
* @brief IO状态检测
* @param
* @return IO_State IO状态枚举
*/
IO_State GetIOState(void)
{
if (P_MK32->CH1_RY_V < -300) return IO_STATE_RISE;
if (P_MK32->CH1_RY_V > 300) return IO_STATE_DESCEND;
return IO_STATE_NONE;
}
/**
* @brief PV参数更新控制
* @param
* @return
*/
void PV_control(void)
{
GV.PV = decoded_PV_variable;
GV.Robot_Move_Speed = ((float)GV.PV.Robot_Move_Speed) / 10;
GV.LaneChangeDistance = GV.PV.Robot_Change_Lane_Distance;
GV.Vertical_Adjust = ((float)GV.PV.Robot_Vertical_Adjust) / 10;
GV.symmetricalOrNot = GV.PV.Robot_symmetricalOrNot;
GV.Robot_backMode = GV.PV.Robot_backMode;
GV.Robot_Swing_Speed = GV.PV.Robot_Swing_Speed;
GV.robot_back_distance = 10;//GV.PV.Robot_Back_Distance;
}
/**
* @brief IV状态参数更新
* @param
* @return
*/
void IV_control(void)
{
GV.PV = decoded_PV_variable;
GV.Vertical_Adjust = ((float)GV.PV.Robot_Vertical_Adjust) / 10;
GV.symmetricalOrNot = GV.PV.Robot_symmetricalOrNot;
GV.Robot_Swing_Speed = GV.PV.Robot_Swing_Speed;
IV.SystemError = GV.SystemErrorData.Com_Error_Code;
IV.Robot_Gyro = GV.TL720DParameters.RF_Angle_Roll;
IV.Is_Online = GV.P_MK32.IsOnline;
IV.Robot_Move_Deri_Speed = GV.Left_Speed_M_min * 10;
IV.LeftCompensation = GV.Left_Compensation;
IV.RightCompensation = GV.Right_Compensation;
IV.Weld_data = (int32_t)(GV.weld_data_X*100);
IV.Weld_exist = GV.weld_exist;
IV.Present_press = GV.Now_press/10;
IV.Turn_difference = GV.turn_center_difference;
IV.left_angle = left_compare_value;
IV.right_angle = right_compare_value;
}
/**
* @brief 姿
* @param chVal
* @param pComp
* @param pCnt
* @return
*/
static void Update_Single_Compensation(int32_t chVal, float* pComp, int* pCnt)
{
if (chVal > COMP_DEADZONE)
{
(*pCnt)++;
if (*pCnt > COMP_COUNT_THRESH)
{
*pComp += COMP_STEP;
*pComp = (*pComp > COMP_LIMIT_MAX) ? COMP_LIMIT_MAX : *pComp;
*pCnt = 0;
}
}
else if (chVal < -COMP_DEADZONE)
{
(*pCnt)--;
if (*pCnt < -COMP_COUNT_THRESH)
{
*pComp -= COMP_STEP;
*pComp = (*pComp < COMP_LIMIT_MIN) ? COMP_LIMIT_MIN : *pComp;
*pCnt = 0;
}
}
else
{
*pCnt = 0;
}
}
/**
* @brief 姿
* @param
* @return
*/
void Compensation_Update(void)
{
static int leftCnt = 0;
static int rightCnt = 0;
// static float Left_Compensation_Degre_100 = 0;
// static float Right_Compensation_Degre_100 = 0;
//
// GV.Left_Compensation = Left_Compensation_Degre_100 / 100.0f;
// GV.Right_Compensation = Right_Compensation_Degre_100 / 100.0f;
Update_Single_Compensation(P_MK32->CH14_LT, &GV.Left_Compensation, &leftCnt);
Update_Single_Compensation(P_MK32->CH15_RT, &GV.Right_Compensation, &rightCnt);
}
void get_weld_data(void)
{
GV.weld_data_X = ReadLazorData->Feature_X;
GV.weld_exist = *Weld_Out_Flag; // 16说明没有焊缝 0说明有焊缝
if((*Weld_Out_Flag)==0)
{
GV.weld_exist = 1; // 16说明没有焊缝 0说明有焊缝
}
else
{
GV.weld_exist = 0;
}
}

20
Bingoo/base/bsp_CV.pb.c

@ -0,0 +1,20 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_CV.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(CV_struct_define, CV_struct_define, AUTO)
#ifndef PB_CONVERT_DOUBLE_FLOAT
/* On some platforms (such as AVR), double is really float.
* To be able to encode/decode double on these platforms, you need.
* to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line.
*/
PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES)
#endif

12
Bingoo/base/bsp_Cmd.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_Cmd.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(Cmd, Cmd, 2)

109
Bingoo/base/bsp_DLT_Log.c

@ -0,0 +1,109 @@
/*
* bsp_DLT_Log.c
*
* Created on: Aug 8, 2024
* Author: akeguo
*/
#include "bsp_DLT_Log.h"
uint32_t GetSysTime(void);
void DltInjectDataRcvd(uint32_t AppId, uint32_t ConId, uint32_t ServId,
uint8_t *Data, uint16_t Size);
void DLT_LowLevelReceiveDmaToIdle(uint8_t *rxBuf, uint16_t size);
void DLT_DataReceiveEndCallback(uint8_t *rxBuf, uint16_t Size);
void DLT_DataTransmit(uint8_t *DltLogData, uint8_t Size);
struct UARTHandler *dLT_Log_UART_Handler;
typedef enum _send_out_port
{
udp = 0, serialport = 1, tcp = 3,
} send_out_port;
char send_out_is_udp_or_serial_port = 0;
void dLT_Log_intialize(struct UARTHandler *Handler)
{
dLT_Log_UART_Handler = Handler;
dLT_Log_UART_Handler->Wait_time = 40;
Handler->dispacherController->Dispacher_Enable = 1;
//log_info("angle_encoder_intialize");
dLT_Log_UART_Handler->UART_Decode = DLT_DataReceiveEndCallback;
/*Register Low Level Transmit/Receive functions for DLTuc Library*/
DLTuc_RegisterTransmitSerialDataFunction(DLT_DataTransmit);
DLTuc_RegisterReceiveSerialDataFunction(DLT_LowLevelReceiveDmaToIdle);
DLTuc_RegisterGetTimeStampMsCallback(GetSysTime); /*Register GetSysTime function*/
/*The function "GetSysTime" must return the time in ms*/
DLTuc_RegisterInjectionDataReceivedCb(DltInjectDataRcvd);
send_out_is_udp_or_serial_port = serialport;
}
//dlt log 日志配置 默认为udp发送
/*This CallBack was registered in main function using function: DLTuc_RegisterTransmitSerialDataFunction*/
void DLT_DataTransmit(uint8_t *DltLogData, uint8_t Size)
{
if (send_out_is_udp_or_serial_port == udp)
{
//udp_dlt_send_back(DltLogData, Size);
}
else if (send_out_is_udp_or_serial_port == serialport)
{
dLT_Log_UART_Handler->AddSendList(dLT_Log_UART_Handler, DltLogData,
Size, 100, NULL);
}
else if (send_out_is_udp_or_serial_port == tcp)
{
//tcp_send_to_all_clients(DltLogData, Size);//
//tcp_add_sendList(DltLogData,Size);
}
DLTuc_MessageTransmitDone();
}
/*CallBacks used by ucDltLibrary section end..*/
void DLT_DataReceiveEndCallback(uint8_t *rxBuf, uint16_t Size)
{
if (Size == 3)
{
if (rxBuf[2])
{
DLT_LOG_ENABLE_LEVEL = 7;
}
else
{
DLT_LOG_ENABLE_LEVEL = 0;
}
}
DLTuc_RawDataReceiveDone(Size);
/*
*In case of STM32 HAL lib, you have to subsitute this function using:
*void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size)
*/
}
//HAL_UARTEx_RxEventCallback
void DLT_LowLevelReceiveDmaToIdle(uint8_t *rxBuf, uint16_t Size)
{
memcpy(rxBuf, dLT_Log_UART_Handler->Rx_Buf, Size);
}
void DltInjectDataRcvd(uint32_t AppId, uint32_t ConId, uint32_t ServId,
uint8_t *Data, uint16_t Size)
{
LOG("RecInjectionData: %s, ServId: %d Size: %d", Data, ServId, Size)
}
uint32_t GetSysTime(void)
{
return HAL_GetTick();
}

570
Bingoo/base/bsp_EEPROM.c

@ -0,0 +1,570 @@
/*
* bsp_EEPROM.c
*
* Created on: Oct 26, 2023
* Author: shiya
*/
#include "BSP/bsp_EEPROM.h"
void bsp_InitI2C(void);
void i2c_Start(void);
void i2c_Stop(void);
void i2c_SendByte(uint8_t _ucByte);
uint8_t i2c_ReadByte(void);
uint8_t i2c_WaitAck(void);
void i2c_Ack(void);
void i2c_NAck(void);
uint8_t i2c_CheckDevice(uint8_t _Address);
uint16_t App_Download_EEPROM_Addr= 1024;
/* 定义读写SCL和SDA的宏 */
#define I2C_SCL_GPIO EEPROM_SCL_GPIO_Port
#define I2C_SDA_GPIO EEPROM_SDA_GPIO_Port
#define I2C_SCL_PIN EEPROM_SCL_Pin
#define I2C_SDA_PIN EEPROM_SDA_Pin
#define I2C_SCL_1() I2C_SCL_GPIO->BSRR = I2C_SCL_PIN /* SCL = 1 */
#define I2C_SCL_0() I2C_SCL_GPIO->BSRR = ((uint32_t)I2C_SCL_PIN << 16U) /* SCL = 0 */
#define I2C_SDA_1() I2C_SDA_GPIO->BSRR = I2C_SDA_PIN /* SDA = 1 */
#define I2C_SDA_0() I2C_SDA_GPIO->BSRR = ((uint32_t)I2C_SDA_PIN << 16U) /* SDA = 0 */
#define I2C_SDA_READ() ((I2C_SDA_GPIO->IDR & I2C_SDA_PIN) != 0) /* 读SDA口线状态 */
#define I2C_SCL_READ() ((I2C_SCL_GPIO->IDR & I2C_SCL_PIN) != 0) /* 读SCL口线状态 */
uint8_t GF_BSP_EEPROM_Init(void)
{
bsp_InitI2C();
return(GF_BSP_EEPROM_CheckOK());
}
/*
*********************************************************************************************************
* : bsp_InitI2C
* : I2C总线的GPIOIO的方式实现
* :
* :
*********************************************************************************************************
*/
void bsp_InitI2C(void)
{
GPIO_InitTypeDef gpio_init;
gpio_init.Mode = GPIO_MODE_OUTPUT_OD; /* 设置开漏输出 */
gpio_init.Pull = GPIO_NOPULL; /* 上下拉电阻不使能 */
gpio_init.Speed = GPIO_SPEED_FREQ_LOW; // GPIO_SPEED_FREQ_HIGH; /* GPIO速度等级 */
gpio_init.Pin = I2C_SCL_PIN;
HAL_GPIO_Init(I2C_SCL_GPIO, &gpio_init);
gpio_init.Pin = I2C_SDA_PIN;
HAL_GPIO_Init(I2C_SDA_GPIO, &gpio_init);
/* 给一个停止信号, 复位I2C总线上的所有设备到待机模式 */
i2c_Stop();
}
/*
*********************************************************************************************************
* : i2c_Delay
* : I2C总线位延迟400KHz
* :
* :
*********************************************************************************************************
*/
static void i2c_Delay(void)
{
GF_BSP_TIMER_DelayUS(2);
}
/*
*********************************************************************************************************
* : i2c_Start
* : CPU发起I2C总线启动信号
* :
* :
*********************************************************************************************************
*/
void i2c_Start(void)
{
/* 当SCL高电平时,SDA出现一个下跳沿表示I2C总线启动信号 */
I2C_SDA_1();
I2C_SCL_1();
i2c_Delay();
I2C_SDA_0();
i2c_Delay();
I2C_SCL_0();
i2c_Delay();
}
/*
*********************************************************************************************************
* : i2c_Start
* : CPU发起I2C总线停止信号
* :
* :
*********************************************************************************************************
*/
void i2c_Stop(void)
{
/* 当SCL高电平时,SDA出现一个上跳沿表示I2C总线停止信号 */
I2C_SDA_0();
i2c_Delay();
I2C_SCL_1();
i2c_Delay();
I2C_SDA_1();
i2c_Delay();
}
/*
*********************************************************************************************************
* : i2c_SendByte
* : CPU向I2C总线设备发送8bit数据
* : _ucByte
* :
*********************************************************************************************************
*/
void i2c_SendByte(uint8_t _ucByte)
{
uint8_t i;
/* 先发送字节的高位bit7 */
for (i = 0; i < 8; i++)
{
if (_ucByte & 0x80)
{
I2C_SDA_1();
}
else
{
I2C_SDA_0();
}
i2c_Delay();
I2C_SCL_1();
i2c_Delay();
I2C_SCL_0();
I2C_SCL_0(); /* 2019-03-14 针对GT811电容触摸,添加一行,相当于延迟几十ns */
if (i == 7)
{
I2C_SDA_1(); // 释放总线
}
_ucByte <<= 1; /* 左移一个bit */
}
}
/*
*********************************************************************************************************
* : i2c_ReadByte
* : CPU从I2C总线设备读取8bit数据
* :
* :
*********************************************************************************************************
*/
uint8_t i2c_ReadByte(void)
{
uint8_t i;
uint8_t value;
/* 读到第1个bit为数据的bit7 */
value = 0;
for (i = 0; i < 8; i++)
{
value <<= 1;
I2C_SCL_1();
i2c_Delay();
if (I2C_SDA_READ())
{
value++;
}
I2C_SCL_0();
i2c_Delay();
}
return value;
}
/*
*********************************************************************************************************
* : i2c_WaitAck
* : CPU产生一个时钟ACK应答信号
* :
* : 01
*********************************************************************************************************
*/
uint8_t i2c_WaitAck(void)
{
uint8_t re;
I2C_SDA_1(); /* CPU释放SDA总线 */
i2c_Delay();
I2C_SCL_1(); /* CPU驱动SCL = 1, 此时器件会返回ACK应答 */
i2c_Delay();
if (I2C_SDA_READ()) /* CPU读取SDA口线状态 */
{
re = 1;
}
else
{
re = 0;
}
I2C_SCL_0();
i2c_Delay();
return re;
}
/*
*********************************************************************************************************
* : i2c_Ack
* : CPU产生一个ACK信号
* :
* :
*********************************************************************************************************
*/
void i2c_Ack(void)
{
I2C_SDA_0(); /* CPU驱动SDA = 0 */
i2c_Delay();
I2C_SCL_1(); /* CPU产生1个时钟 */
i2c_Delay();
I2C_SCL_0();
i2c_Delay();
I2C_SDA_1(); /* CPU释放SDA总线 */
i2c_Delay();
}
/*
*********************************************************************************************************
* : i2c_NAck
* : CPU产生1个NACK信号
* :
* :
*********************************************************************************************************
*/
void i2c_NAck(void)
{
I2C_SDA_1(); /* CPU驱动SDA = 1 */
i2c_Delay();
I2C_SCL_1(); /* CPU产生1个时钟 */
i2c_Delay();
I2C_SCL_0();
i2c_Delay();
}
/*
*********************************************************************************************************
* : i2c_CheckDevice
* : I2C总线设备CPU向发送设备地址
* : _AddressI2C总线地址
* : 0 1
*********************************************************************************************************
*/
uint8_t i2c_CheckDevice(uint8_t _Address)
{
uint8_t ucAck;
if (I2C_SDA_READ() && I2C_SCL_READ())
{
i2c_Start(); /* 发送启动信号 */
/* 发送设备地址+读写控制bit(0 = w, 1 = r) bit7 先传 */
i2c_SendByte(_Address | I2C_WR);
ucAck = i2c_WaitAck(); /* 检测设备的ACK应答 */
i2c_Stop(); /* 发送停止信号 */
return ucAck;
}
return 1; /* I2C总线异常 */
}
/*
*********************************************************************************************************
* : ee_CheckOk
* : EERPOM是否正常
* :
* : 1 0
*********************************************************************************************************
*/
uint8_t GF_BSP_EEPROM_CheckOK(void)
{
if (i2c_CheckDevice(EE_DEV_ADDR) == 0)
{
return 1;
}
else
{
/* 失败后,切记发送I2C总线停止信号 */
i2c_Stop();
return 0;
}
}
/*
*********************************************************************************************************
* : GF_BSP_EEPROM_ReadBytes
* : EEPROM指定地址处开始读取若干数据
* : _usAddress :
* _usSize :
* _pReadBuf :
* : 0 1
*********************************************************************************************************
*/
uint8_t GF_BSP_EEPROM_ReadBytes(uint8_t *_pReadBuf, uint16_t _usAddress, uint16_t _usSize)
{
uint16_t i;
/* 采用串行EEPROM随即读取指令序列,连续读取若干字节 */
/* 第1步:发起I2C总线启动信号 */
i2c_Start();
/* 第2步:发起控制字节,高7bit是地址,bit0是读写控制位,0表示写,1表示读 */
i2c_SendByte(EE_DEV_ADDR | I2C_WR); /* 此处是写指令 */
/* 第3步:发送ACK */
if (i2c_WaitAck() != 0)
{
goto cmd_fail; /* EEPROM器件无应答 */
}
/* 第4步:发送字节地址,24C02只有256字节,因此1个字节就够了,如果是24C04以上,那么此处需要连发多个地址 */
if (EE_ADDR_BYTES == 1)
{
i2c_SendByte((uint8_t)_usAddress);
if (i2c_WaitAck() != 0)
{
goto cmd_fail; /* EEPROM器件无应答 */
}
}
else
{
i2c_SendByte(_usAddress >> 8);
if (i2c_WaitAck() != 0)
{
goto cmd_fail; /* EEPROM器件无应答 */
}
i2c_SendByte(_usAddress&0xff);
if (i2c_WaitAck() != 0)
{
goto cmd_fail; /* EEPROM器件无应答 */
}
}
/* 第6步:重新启动I2C总线。下面开始读取数据 */
i2c_Start();
/* 第7步:发起控制字节,高7bit是地址,bit0是读写控制位,0表示写,1表示读 */
i2c_SendByte(EE_DEV_ADDR | I2C_RD); /* 此处是读指令 */
/* 第8步:发送ACK */
if (i2c_WaitAck() != 0)
{
goto cmd_fail; /* EEPROM器件无应答 */
}
/* 第9步:循环读取数据 */
for (i = 0; i < _usSize; i++)
{
_pReadBuf[i] = i2c_ReadByte(); /* 读1个字节 */
/* 每读完1个字节后,需要发送Ack, 最后一个字节不需要Ack,发Nack */
if (i != _usSize - 1)
{
i2c_Ack(); /* 中间字节读完后,CPU产生ACK信号(驱动SDA = 0) */
}
else
{
i2c_NAck(); /* 最后1个字节读完后,CPU产生NACK信号(驱动SDA = 1) */
}
}
/* 发送I2C总线停止信号 */
i2c_Stop();
return 1; /* 执行成功 */
cmd_fail: /* 命令执行失败后,切记发送停止信号,避免影响I2C总线上其他设备 */
/* 发送I2C总线停止信号 */
i2c_Stop();
return 0;
}
/*
*********************************************************************************************************
* : GF_BSP_EEPROM_WriteBytes
* : EEPROM指定地址写入若干数据
* : _usAddress :
* _usSize :
* _pWriteBuf :
* : 0 1
*********************************************************************************************************
*/
uint8_t GF_BSP_EEPROM_WriteBytes(uint8_t *_pWriteBuf, uint16_t _usAddress, uint16_t _usSize)
{
uint16_t i,m;
uint16_t usAddr;
/*
EEPROM不像读操作可以连续读取很多字节page
24xx02page size = 8
1
: page wirte操作
*/
usAddr = _usAddress;
for (i = 0; i < _usSize; i++)
{
/* 当发送第1个字节或是页面首地址时,需要重新发起启动信号和地址 */
if ((i == 0) || (usAddr & (EE_PAGE_SIZE - 1)) == 0)
{
/* 第0步:发停止信号,启动内部写操作 */
i2c_Stop();
/* 通过检查器件应答的方式,判断内部写操作是否完成, 一般小于 10ms
CLK频率为200KHz时30
*/
for (m = 0; m < 1000; m++)
{
/* 第1步:发起I2C总线启动信号 */
i2c_Start();
/* 第2步:发起控制字节,高7bit是地址,bit0是读写控制位,0表示写,1表示读 */
i2c_SendByte(EE_DEV_ADDR | I2C_WR); /* 此处是写指令 */
/* 第3步:发送一个时钟,判断器件是否正确应答 */
if (i2c_WaitAck() == 0)
{
break;
}
}
if (m == 1000)
{
goto cmd_fail; /* EEPROM器件写超时 */
}
/* 第4步:发送字节地址,24C02只有256字节,因此1个字节就够了,如果是24C04以上,那么此处需要连发多个地址 */
if (EE_ADDR_BYTES == 1)
{
i2c_SendByte((uint8_t)usAddr);
if (i2c_WaitAck() != 0)
{
goto cmd_fail; /* EEPROM器件无应答 */
}
}
else
{
i2c_SendByte(usAddr >> 8);
if (i2c_WaitAck() != 0)
{
goto cmd_fail; /* EEPROM器件无应答 */
}
i2c_SendByte(usAddr&0xff);
if (i2c_WaitAck() != 0)
{
goto cmd_fail; /* EEPROM器件无应答 */
}
}
}
/* 第6步:开始写入数据 */
i2c_SendByte(_pWriteBuf[i]);
/* 第7步:发送ACK */
if (i2c_WaitAck() != 0)
{
goto cmd_fail; /* EEPROM器件无应答 */
}
usAddr++; /* 地址增1 */
}
/* 命令执行成功,发送I2C总线停止信号 */
i2c_Stop();
/* 通过检查器件应答的方式,判断内部写操作是否完成, 一般小于 10ms
CLK频率为200KHz时30
*/
for (m = 0; m < 1000; m++)
{
/* 第1步:发起I2C总线启动信号 */
i2c_Start();
/* 第2步:发起控制字节,高7bit是地址,bit0是读写控制位,0表示写,1表示读 */
#if EE_ADDR_A8 == 1
i2c_SendByte(EE_DEV_ADDR | I2C_WR | ((_usAddress >> 7) & 0x0E)); /* 此处是写指令 */
#else
i2c_SendByte(EE_DEV_ADDR | I2C_WR); /* 此处是写指令 */
#endif
/* 第3步:发送一个时钟,判断器件是否正确应答 */
if (i2c_WaitAck() == 0)
{
break;
}
}
if (m == 1000)
{
goto cmd_fail; /* EEPROM器件写超时 */
}
/* 命令执行成功,发送I2C总线停止信号 */
i2c_Stop();
return 1;
cmd_fail: /* 命令执行失败后,切记发送停止信号,避免影响I2C总线上其他设备 */
/* 发送I2C总线停止信号 */
i2c_Stop();
return 0;
}
CV_struct_define GF_BSP_EEPROM_Get_CV(void)
{
CV_struct_define cv= {0};
//char buffer[sizeof(CV_struct_define)];
GF_BSP_EEPROM_ReadBytes(&cv, GF_BSP_EEPROM_CV_struct_define_Start_Address, sizeof(CV_struct_define));
return cv;
}
uint8_t GF_BSP_EEPROM_Set_CV(CV_struct_define cv)
{
return GF_BSP_EEPROM_WriteBytes((uint8_t*)&cv,GF_BSP_EEPROM_CV_struct_define_Start_Address,sizeof(CV_struct_define));
}
IAP_struct_define GF_BSP_EEPROM_Get_IAP(void)
{
IAP_struct_define iap= {0};
GF_BSP_EEPROM_ReadBytes(&iap, IAP_struct_define_Start_Address, sizeof(IAP_struct_define));
return iap;
}
uint8_t GF_BSP_EEPROM_Set_IAP(IAP_struct_define iap)
{
return GF_BSP_EEPROM_WriteBytes((uint8_t*)&iap,IAP_struct_define_Start_Address,sizeof(IAP_struct_define));
}
//PV_struct_define GF_BSP_EEPROM_Get_PV(void)
//{
// CV_struct_define cv=GF_BSP_EEPROM_Get_CV();
//
// return cv.PV;
//
//}
//uint8_t GF_BSP_EEPROM_Set_PV(PV_struct_define pv)
//{
// CV_struct_define cv=GF_BSP_EEPROM_Get_CV();
// cv.PV=pv;
// return GF_BSP_EEPROM_Set_CV(cv);
//}

13
Bingoo/base/bsp_Error.pb.c

@ -0,0 +1,13 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_Error.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(ErrorData, ErrorData, AUTO)

31
Bingoo/base/bsp_Error_Detect.c

@ -0,0 +1,31 @@
/*
* bsp_Error_Detect.c
*
* Created on: Oct 23, 2024
* Author: akeguo
*/
#include "bsp_Error_Detect.h"
void ErrorDetect();
char Error_Detect_Enable=1;
HardWareController *HardWareErrorController;
void Error_Detect_Intialzie(uint16_t DispacherPeriod)
{
HardWareErrorController = (HardWareController*) malloc(
sizeof(HardWareController));
HardWareErrorController->pComHWHead = NULL;
HardWareErrorController->pComHWTail = NULL;
HardWareErrorController->Add_PCOMHardWare = ComHardWare_List_Add_t;
HardWareErrorController->Set_PCOMHardWare = Set_PCOMHardWare_t;
HardWareErrorController->PCOMHardWare_Check = PCOMHardWare_Check_t;
HardWareErrorController->DispacherCallTime = DispacherPeriod;//check the communicaton every 50ms
GF_BSP_Interrupt_Add_CallBack(
DF_BSP_InterCall_TIM8_2ms_PeriodElapsedCallback, ErrorDetect);
}
void ErrorDetect()
{
if (Error_Detect_Enable == 1)
{
HardWareErrorController->PCOMHardWare_Check(HardWareErrorController);
}
}

334
Bingoo/base/bsp_FDCAN.c

@ -0,0 +1,334 @@
/*
* bsp_FDCAN.c
*
* Created on: Oct 26, 2023
* Author: shiya
*/
#include "bsp_FDCAN.h"
#include "main.h"
#include <stdlib.h>
#include "bsp_Error.pb.h"
//#include "MSP/msp_TI5MOTOR.h"
FDCANHandler FD_CAN_1_Handler;
FDCANHandler FD_CAN_2_Handler;
FDCAN_RxHeaderTypeDef CAN_RX_HDR;
uint8_t CAN_Buf[8];
uint8_t CAN_Buf_2[8];
int32_t CAN_ID;
int32_t CAN_ID_2;
uint8_t GF_BSP_FDCAN_Init(void) //can初始化
{
if (HAL_FDCAN_ActivateNotification(&hfdcan1, FDCAN_IT_RX_FIFO0_NEW_MESSAGE,
0) != HAL_OK)
{
Error_Handler();
}
if (HAL_FDCAN_ActivateNotification(&hfdcan1, FDCAN_IT_BUS_OFF, 0) != HAL_OK)
{
Error_Handler();
}
HAL_FDCAN_Start(&hfdcan1);
if (HAL_FDCAN_ActivateNotification(&hfdcan2, FDCAN_IT_RX_FIFO0_NEW_MESSAGE,
0) != HAL_OK)
{
Error_Handler();
}
if (HAL_FDCAN_ActivateNotification(&hfdcan2, FDCAN_IT_BUS_OFF, 0) != HAL_OK)
{
Error_Handler();
}
HAL_FDCAN_Start(&hfdcan2);
return 1;
}
void HAL_FDCAN_ErrorStatusCallback(FDCAN_HandleTypeDef *hfdcan,
uint32_t ErrorStatusITs)
{
if (hfdcan->Instance == FDCAN1)
{
MX_FDCAN1_Init();
}
if (hfdcan->Instance == FDCAN2)
{
MX_FDCAN2_Init();
}
}
void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo0ITs)//can接收
{
if (hfdcan->Instance == FDCAN1)
{
if (HAL_FDCAN_GetRxMessage(hfdcan, FDCAN_RX_FIFO0, &CAN_RX_HDR, CAN_Buf)//把数据存CAN_Buf里
== HAL_OK)
{
CAN_ID = FD_CAN_1_Handler.ReceivedFrameID =
(uint32_t) CAN_RX_HDR.Identifier; //ID
#if NewCANSendVersion
FD_CAN_1_Handler.ReceivedLength = (uint32_t) CAN_RX_HDR.DataLength;//接收长度
#else
FD_CAN_1_Handler.ReceivedLength = (uint32_t) CAN_RX_HDR.DataLength>>16;
#endif
if (FD_CAN_1_Handler.CAN_Decode != NULL )
{
FD_CAN_1_Handler.CAN_Decode(FD_CAN_1_Handler.ReceivedFrameID,
CAN_Buf, FD_CAN_1_Handler.ReceivedLength);
}
GF_BSP_Interrupt_Run_CallBack(DF_BSP_InterCall_FDCAN1_RxFifo0Callback);
}
} else if (hfdcan->Instance == FDCAN2)
{
if (HAL_FDCAN_GetRxMessage(hfdcan, FDCAN_RX_FIFO0, &CAN_RX_HDR,
CAN_Buf_2) == HAL_OK) ////把数据存CAN_Buf2里
{
CAN_ID_2 = FD_CAN_2_Handler.ReceivedFrameID =
(uint32_t) CAN_RX_HDR.Identifier;
#if NewCANSendVersion
FD_CAN_2_Handler.ReceivedLength = (uint32_t) CAN_RX_HDR.DataLength;
#else
FD_CAN_2_Handler.ReceivedLength = (uint32_t) CAN_RX_HDR.DataLength>>16;
#endif
if (FD_CAN_2_Handler.CAN_Decode != NULL)
{
FD_CAN_2_Handler.CAN_Decode(FD_CAN_2_Handler.ReceivedFrameID,
CAN_Buf_2, FD_CAN_2_Handler.ReceivedLength);
}
GF_BSP_Interrupt_Run_CallBack(DF_BSP_InterCall_FDCAN2_RxFifo0Callback);
}
}
}
FDCAN_TxHeaderTypeDef TXHeader1;
FDCAN_TxHeaderTypeDef TXHeader2;
void GF_BSP_CANHandler_Init(int can1_sendListPeriod, int can1_DispacherPeriod,
int can2_sendListPeriod, int can2_DispacherPeriod)
{
GF_BSP_CANHandler_Init_CAN(&FD_CAN_1_Handler, &hfdcan1, can1_sendListPeriod,
can1_DispacherPeriod);
GF_BSP_CANHandler_Init_CAN(&FD_CAN_2_Handler, &hfdcan2, can2_sendListPeriod,
can2_DispacherPeriod);
GF_BSP_Interrupt_Add_CallBack(
DF_BSP_InterCall_TIM8_2ms_PeriodElapsedCallback, GF_BSP_CAN_Timer);//2ms一次
}
/******************CAN初始化************************/
void GF_BSP_CANHandler_Init_CAN(FDCANHandler *handler,
FDCAN_HandleTypeDef *canfd, int sendListPeriod, int DispacherPeriod)
{
handler->canfd = canfd; //FD_CAN_1_Handler的的canfd与 FDCAN_HandleTypeDef hfdcan1;绑定
handler->dispacherController = (DispacherController*) malloc(
sizeof(DispacherController));
handler->dispacherController->pHead = NULL;
handler->dispacherController->pTail = NULL;
handler->dispacherController->Dispacher_Enable = 1;
handler->dispacherController->DispacherCallTime = DispacherPeriod ; // call the function every 50 ms
handler->dispacherController->Dispacher_Counter = 0;
handler->dispacherController->DispacherNumber = 0;
handler->dispacherController->Add_Dispatcher_List = Dispatcher_List_Add_t;
handler->dispacherController->Dispatcher_Run = Dispatch_t;
handler->timeSpan = 2;
handler->SendList_time_Count = 0;
handler->AddCANSendList = CANHandlerAddTxList;
handler->SendList_Period = sendListPeriod;
handler->CAN_Send = CAN_Send_t;
handler->CAN_Send_Data = CAN_Send_Data_t;
}
DispacherController *can_dispacherController;
HardWareController *can_HardWareController;
//2ms
void GF_BSP_CAN_Timer()
{
can_dispacherController = FD_CAN_1_Handler.dispacherController;
if (FD_CAN_1_Handler.pCurrentCANSendHadler != NULL)
{
GF_CAN_Send_List_Send(&FD_CAN_1_Handler);
} else
{
can_dispacherController = FD_CAN_1_Handler.dispacherController;
can_dispacherController->Dispatcher_Run(can_dispacherController);
}
if (FD_CAN_2_Handler.pCurrentCANSendHadler != NULL)
{
GF_CAN_Send_List_Send(&FD_CAN_2_Handler);
} else
{
can_dispacherController = FD_CAN_2_Handler.dispacherController;
can_dispacherController->Dispatcher_Run(can_dispacherController);
}
}
//发送函数 在上面定时器调用 2ms一次
void GF_CAN_Send_List_Send(FDCANHandler *handler)
{
handler->SendList_time_Count++;
//timeSpan-->2 SendList_Period-->2
if (handler->timeSpan * handler->SendList_time_Count
>= handler->SendList_Period)
{
handler->SendList_time_Count = 0;
handler->SendListExists = 1;
if (handler->pCurrentCANSendHadler != NULL)
{
//拷贝数据到相关的代码中,然后发送
handler->SendFrameID=handler->pCurrentCANSendHadler->CAN_ID;
memcpy(handler->Tx_Buf, handler->pCurrentCANSendHadler->Tx_Buf,
handler->pCurrentCANSendHadler->SendLength);
handler->SendList_Period=handler->pCurrentCANSendHadler->SendListTimePeriod;//发送周期
handler->SendLength = handler->pCurrentCANSendHadler->SendLength;
handler->CAN_Send_Data(handler); /***********发送*****************/
if (handler->pCurrentCANSendHadler->pNext != NULL)
{
CANSendHandler *temp = handler->pCurrentCANSendHadler->pNext;
free(handler->pCurrentCANSendHadler); //清除内存
handler->pCurrentCANSendHadler = temp;
} else
{
free(handler->pCurrentCANSendHadler); //清除内存
handler->pCurrentCANSendHadler = NULL;
}
} else
{
handler->SendListExists = 0;
}
}
}
//
//handler->CAN_Send_Data = CAN_Send_Data_t;
void CAN_Send_Data_t(struct _FDCANHandler *fd)
{
CAN_Send_t(fd, fd->SendFrameID, fd->SendLength, fd->Tx_Buf);
}
/*
* |
* |
* V
* */
void CAN_Send_t(struct _FDCANHandler *fd, uint32_t FrameID, uint8_t DataLength,
uint8_t *Txdata)
{
//Function_code = Txdata[0];
if (DataLength > 8)
{
return;
}
if (fd->canfd == &hfdcan1)
{
TXHeader1.BitRateSwitch = FDCAN_BRS_OFF;
#if NewCANSendVersion
TXHeader1.DataLength = (uint32_t) DataLength ;
#else
TXHeader1.DataLength = (uint32_t) DataLength << 16; //数据长度大于8的话会有错误
#endif
TXHeader1.FDFormat = FDCAN_CLASSIC_CAN;
TXHeader1.IdType = FDCAN_STANDARD_ID;
TXHeader1.Identifier = FrameID;
TXHeader1.TxFrameType = FDCAN_DATA_FRAME;
HAL_FDCAN_AddMessageToTxFifoQ(&hfdcan1, &TXHeader1, Txdata);
} else if (fd->canfd == &hfdcan2)
{
TXHeader2.BitRateSwitch = FDCAN_BRS_OFF;
#if NewCANSendVersion
TXHeader2.DataLength = (uint32_t) DataLength ;
#else
TXHeader2.DataLength = (uint32_t) DataLength << 16; //数据长度大于8的话会有错误
#endif
//TXHeader2.DataLength = (uint32_t) DataLength << 16; //数据长度大于8的话会有错误
TXHeader2.FDFormat = FDCAN_CLASSIC_CAN;
TXHeader2.IdType = FDCAN_STANDARD_ID;
TXHeader2.Identifier = FrameID;
TXHeader2.TxFrameType = FDCAN_DATA_FRAME;
HAL_FDCAN_AddMessageToTxFifoQ(&hfdcan2, &TXHeader2, Txdata);
}
}
//handler->AddCANSendList = CANHandlerAddTxList;该函数由AddCANSendList调用
//把多个 CAN 消息按顺序添加到发送队列。系统按照设定的时间周期或者优先级依次发送队列中的消息。
/*
* Motor_Controller->AddCANSendList(Motor_Controller, 0x600 + MotorID, 8,
Motor_Controller->Tx_Buf, WaitTime, NULL);
* */
void CANHandlerAddTxList(FDCANHandler *handler, uint32_t CAN_ID,
uint8_t SendLength, uint8_t *Tx_Buf,uint32_t sendListTimePeriod,
void (*CAN_Decode)(uint32_t, uint8_t*, uint32_t)) //参数其实就是一组can数据 在FDHandler添加东西
{
CANSendHandler *pTmp = NULL; //临时指针 链表中的节点
//临时指针2用于逐个申请内存
pTmp = (CANSendHandler*) malloc(sizeof(CANSendHandler));//节点申请内存
memcpy(pTmp->Tx_Buf, Tx_Buf, SendLength);//把参数2的内容复制到节点上
pTmp->pNext = NULL; //下一个节点暂时为空
pTmp->CAN_ID=CAN_ID; //设置节点ID
pTmp->SendLength = SendLength;
//pTmp->CAN_Decode = CAN_Decode;
pTmp->SendListTimePeriod=sendListTimePeriod;//节点的发送周期
//if NULL, call intialize one
if (handler->pCurrentCANSendHadler == NULL)
{
handler->pCurrentCANSendHadler = pTmp; //空链表
} else
{
char i = 0;
//插到尾部
CANSendHandler *phead = NULL;
phead = handler->pCurrentCANSendHadler;
while (phead->pNext != NULL)
{
i++;
phead = phead->pNext;
}
phead->pNext = pTmp;
}
}

104
Bingoo/base/bsp_GPIO.c

@ -0,0 +1,104 @@
/*
* bsp_GPIO.c
*
* Created on: Oct 26, 2023
* Author: shiya
*/
#include "BSP/bsp_GPIO.h"
uint8_t GF_BSP_GPIO_Init()
{
return 1;
}
/* IO配置
* IO_Index : 0-5
* Level : 0:PIN_RESET; 1:PIN_SET;
* */
void GF_BSP_GPIO_SetIO(uint8_t IO_Index,uint8_t Level)
{
GPIO_PinState PinState;
if(Level == 0)
PinState=GPIO_PIN_RESET;
else
PinState=GPIO_PIN_SET;
switch(IO_Index)
{
case 0:
HAL_GPIO_WritePin(OUT_0_GPIO_Port, OUT_0_Pin, PinState);
break;
case 1:
HAL_GPIO_WritePin(OUT_1_GPIO_Port, OUT_1_Pin, PinState);//pc3
break;
case 2:
HAL_GPIO_WritePin(OUT_2_GPIO_Port, OUT_2_Pin, PinState);
break;
case 3:
HAL_GPIO_WritePin(OUT_3_GPIO_Port, OUT_3_Pin, PinState);
break;
case 4:
HAL_GPIO_WritePin(OUT_4_GPIO_Port, OUT_4_Pin, PinState);
break;
case 5:
HAL_GPIO_WritePin(OUT_5_GPIO_Port, OUT_5_Pin, PinState);
break;
}
}
uint8_t GF_BSP_GPIO_ToggleIO(uint8_t IO_Index)
{
switch(IO_Index)
{
case 0:
HAL_GPIO_TogglePin(OUT_0_GPIO_Port, OUT_0_Pin);
break;
case 1:
HAL_GPIO_TogglePin(OUT_1_GPIO_Port, OUT_1_Pin);
break;
case 2:
HAL_GPIO_TogglePin(OUT_2_GPIO_Port, OUT_2_Pin);
break;
case 3:
HAL_GPIO_TogglePin(OUT_3_GPIO_Port, OUT_3_Pin);
break;
case 4:
HAL_GPIO_TogglePin(OUT_4_GPIO_Port, OUT_4_Pin);
break;
case 5:
HAL_GPIO_TogglePin(OUT_5_GPIO_Port, OUT_5_Pin);
break;
}
}
uint8_t GF_BSP_GPIO_ReadIO(uint8_t IO_Index)
{
GPIO_PinState PinState;
switch(IO_Index)
{
case 0:
PinState = HAL_GPIO_ReadPin(IN_0_GPIO_Port, IN_0_Pin);
break;
case 1:
PinState = HAL_GPIO_ReadPin(IN_1_GPIO_Port, IN_1_Pin);
break;
case 2:
PinState = HAL_GPIO_ReadPin(IN_2_GPIO_Port, IN_2_Pin);
break;
case 3:
PinState = HAL_GPIO_ReadPin(IN_3_GPIO_Port, IN_3_Pin);
break;
case 4:
PinState = HAL_GPIO_ReadPin(IN_4_GPIO_Port, IN_4_Pin);
break;
case 5:
PinState = HAL_GPIO_ReadPin(IN_5_GPIO_Port, IN_5_Pin);
break;
}
return((uint8_t)PinState);
}

12
Bingoo/base/bsp_GV.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_GV.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(GV_struct_define, GV_struct_define, 2)

12
Bingoo/base/bsp_IAP.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_IAP.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(IAP_struct_define, IAP_struct_define, AUTO)

41
Bingoo/base/bsp_INTERCALL.c

@ -0,0 +1,41 @@
/*
* bsp_INTERCALL.c
*
* Created on: 2023118
* Author: shiya
*/
#include "BSP/bsp_include.h"
typedef struct
{
uint8_t num; //调用函数指针数量
void(*fn[DF_BSP_InterCall_Num])(void); //被调用函数指针,最多20个回调函数
}SD_BSP_InterCall;
SD_BSP_InterCall V_BSP_InterCall_Array[DF_BSP_InterCall_Type_Num] = {0};
//给中断函数链接一个回调函数,直接添加空函数指针
//返回值1表示添加成功,返回值0表示添加失败
uint8_t GF_BSP_Interrupt_Add_CallBack(enum DF_BSP_InterCall_Type _type,void(*_fn)(void))
{
V_BSP_InterCall_Array[_type].num++;
if(V_BSP_InterCall_Array[_type].num>=DF_BSP_InterCall_Num)
{
return 0;
}
V_BSP_InterCall_Array[_type].fn[V_BSP_InterCall_Array[_type].num-1]=_fn;
return 1;
}
//放到中断函数中,运行相应的回调函数,有几个运行几个
void GF_BSP_Interrupt_Run_CallBack(enum DF_BSP_InterCall_Type _type)
{
uint8_t i=0;
if(V_BSP_InterCall_Array[_type].num>0)
{
for(i=0;i<V_BSP_InterCall_Array[_type].num;i++)
{
(*(V_BSP_InterCall_Array[_type].fn[i]))();
}
}
}

12
Bingoo/base/bsp_IO.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_IO.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(IO_Data, IO_Data, AUTO)

12
Bingoo/base/bsp_IV.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_IV.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(IV_struct_define, IV_struct_define, AUTO)

372
Bingoo/base/bsp_MB_host.c

@ -0,0 +1,372 @@
#include "bsp_MB_host.h"
#include "stdio.h"
#include "BSP/bsp_UART.h"
//__IO uint8_t Rx_Buf[256]; // 接收缓存,最大256字节
__IO uint8_t Tx_Buf[256]; // 发送缓存,最大256字节
__IO uint8_t tmp_Rx_Buf; // 临时接收缓存
__IO uint16_t RxCount = 0; // 接收字符计数
uint8_t MB_rx_flag = 0;
uint16_t Read_Reg_Num;
uint8_t Read_Slave_ID = 0;
/* 私有类型定义 --------------------------------------------------------------*/
/* 私有宏定义 ----------------------------------------------------------------*/
/* 私有变量 ------------------------------------------------------------------*/
// CRC 高位字节值表
static const uint8_t auchCRCHi[] =
{ 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01,
0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01,
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40 };
// CRC 低位字节值表
static const uint8_t auchCRCLo[] =
{ 0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7, 0x05,
0xC5, 0xC4, 0x04, 0xCC, 0x0C, 0x0D, 0xCD, 0x0F, 0xCF, 0xCE, 0x0E, 0x0A,
0xCA, 0xCB, 0x0B, 0xC9, 0x09, 0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9, 0x1B,
0xDB, 0xDA, 0x1A, 0x1E, 0xDE, 0xDF, 0x1F, 0xDD, 0x1D, 0x1C, 0xDC, 0x14,
0xD4, 0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2, 0x12, 0x13, 0xD3, 0x11,
0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, 0xF2, 0x32, 0x36,
0xF6, 0xF7, 0x37, 0xF5, 0x35, 0x34, 0xF4, 0x3C, 0xFC, 0xFD, 0x3D, 0xFF,
0x3F, 0x3E, 0xFE, 0xFA, 0x3A, 0x3B, 0xFB, 0x39, 0xF9, 0xF8, 0x38, 0x28,
0xE8, 0xE9, 0x29, 0xEB, 0x2B, 0x2A, 0xEA, 0xEE, 0x2E, 0x2F, 0xEF, 0x2D,
0xED, 0xEC, 0x2C, 0xE4, 0x24, 0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26, 0x22,
0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60, 0x61, 0xA1, 0x63,
0xA3, 0xA2, 0x62, 0x66, 0xA6, 0xA7, 0x67, 0xA5, 0x65, 0x64, 0xA4, 0x6C,
0xAC, 0xAD, 0x6D, 0xAF, 0x6F, 0x6E, 0xAE, 0xAA, 0x6A, 0x6B, 0xAB, 0x69,
0xA9, 0xA8, 0x68, 0x78, 0xB8, 0xB9, 0x79, 0xBB, 0x7B, 0x7A, 0xBA, 0xBE,
0x7E, 0x7F, 0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5, 0x77,
0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71, 0x70, 0xB0, 0x50,
0x90, 0x91, 0x51, 0x93, 0x53, 0x52, 0x92, 0x96, 0x56, 0x57, 0x97, 0x55,
0x95, 0x94, 0x54, 0x9C, 0x5C, 0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E, 0x5A,
0x9A, 0x9B, 0x5B, 0x99, 0x59, 0x58, 0x98, 0x88, 0x48, 0x49, 0x89, 0x4B,
0x8B, 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C, 0x44,
0x84, 0x85, 0x45, 0x87, 0x47, 0x46, 0x86, 0x82, 0x42, 0x43, 0x83, 0x41,
0x81, 0x80, 0x40 };
/**
* : Modbus CRC16
* : pushMsg:,usDataLen:
* : CRC16
* : ,
*/
uint16_t MB_CRC16(uint8_t *pushMsg, uint16_t usDataLen)
{
uint8_t uchCRCHi = 0xFF;
uint8_t uchCRCLo = 0xFF;
uint16_t uIndex;
while (usDataLen--)
{
uIndex = uchCRCLo ^ *pushMsg++;
uchCRCLo = uchCRCHi ^ auchCRCHi[uIndex];
uchCRCHi = auchCRCLo[uIndex];
}
return (uchCRCHi << 8 | uchCRCLo);
}
/**
* : N个线圈状态(CoilStatue)
* : _addr:,_reg:,_num:
* :
* : ,
*/
void MB_ReadCoil(uint8_t *Tx_Buf, uint8_t *TxCount_t, uint8_t _addr,
uint16_t _reg, uint16_t _num)
{
uint16_t TxCount = 0;
uint16_t crc = 0;
Tx_Buf[TxCount++] = _addr; /* 从站地址 */
Tx_Buf[TxCount++] = 0x01; /* 功能码 */
Tx_Buf[TxCount++] = _reg >> 8; /* 寄存器地址 高字节 */
Tx_Buf[TxCount++] = _reg; /* 寄存器地址 低字节 */
Tx_Buf[TxCount++] = _num >> 8; /* 线圈(bit)个数 高字节 */
Tx_Buf[TxCount++] = _num; /* 线圈(bit)个数 低字节 */
crc = MB_CRC16(Tx_Buf, TxCount);
Tx_Buf[TxCount++] = crc; /* crc 低字节 */
Tx_Buf[TxCount++] = crc >> 8; /* crc 高字节 */
*TxCount_t = TxCount;
//uartHandler->UART_Tx(uartHandler,(uint8_t *)&Tx_Buf,TxCount);
//UART_Tx((uint8_t *)&Tx_Buf,TxCount);
}
/**
* : 线(CoilStatue)
* : _addr:,_reg:,_sta:线(0,1)
* :
* : ,
*/
void MB_WriteCoil(uint8_t *Tx_Buf, uint8_t *TxCount_t, uint8_t _addr,
uint16_t _reg, uint16_t _sta)
{
uint16_t TxCount = 0;
uint16_t crc = 0;
Tx_Buf[TxCount++] = _addr; /* 从站地址 */
Tx_Buf[TxCount++] = 0x05; /* 功能码 */
Tx_Buf[TxCount++] = _reg >> 8; /* 寄存器地址 高字节 */
Tx_Buf[TxCount++] = _reg; /* 寄存器地址 低字节 */
Tx_Buf[TxCount++] = _sta >> 8; /* 线圈(bit)个数 高字节 */
Tx_Buf[TxCount++] = _sta; /* 线圈(bit)个数 低字节 */
crc = MB_CRC16(Tx_Buf, TxCount);
Tx_Buf[TxCount++] = crc; /* crc 低字节 */
Tx_Buf[TxCount++] = crc >> 8; /* crc 高字节 */
*TxCount_t = TxCount;
//UART_Tx((uint8_t *)&Tx_Buf,TxCount);
//uartHandler->UART_Tx(uartHandler,(uint8_t *)&Tx_Buf,TxCount);
}
void MB_WriteNumCoil(uint8_t *Tx_Buf, uint8_t *TxCount_t, uint8_t _addr,
uint16_t _reg, uint16_t _num, uint8_t *_databuf)
{
uint16_t i;
uint16_t TxCount = 0;
uint16_t crc = 0;
Tx_Buf[TxCount++] = _addr; /* 从站地址 */
Tx_Buf[TxCount++] = 0x0F; /* 功能码 */
Tx_Buf[TxCount++] = _reg >> 8; /* 寄存器地址 高字节 */
Tx_Buf[TxCount++] = _reg; /* 寄存器地址 低字节 */
Tx_Buf[TxCount++] = _num >> 8; /* 寄存器(16bits)个数 高字节 */
Tx_Buf[TxCount++] = _num; /* 低字节 */
if(_num%8==0)
{
Tx_Buf[TxCount++] = _num / 8;
}else
{
Tx_Buf[TxCount++] = _num / 8 + 1;
}
/* 数据个数 */
uint16_t ij=TxCount++;
for (i = 0; i < _num; i++)
{
Tx_Buf[ij]|= _databuf[i]<<i; /* 后面的数据长度 */
}
crc = MB_CRC16(Tx_Buf, TxCount);
Tx_Buf[TxCount++] = crc; /* crc 低字节 */
Tx_Buf[TxCount++] = crc >> 8; /* crc 高字节 */
//UART_Tx((uint8_t *)&Tx_Buf,TxCount);
*TxCount_t = TxCount;
}
/**
* : (InputStatue)
* : _addr:,_reg:,_num:
* :
* : ,
*/
void MB_ReadInput(uint8_t *Tx_Buf, uint8_t *TxCount_t, uint8_t _addr,
uint16_t _reg, uint16_t _num)
{
uint16_t TxCount = 0;
uint16_t crc = 0;
Tx_Buf[TxCount++] = _addr; /* 从站地址 */
Tx_Buf[TxCount++] = 0x02; /* 功能码 */
Tx_Buf[TxCount++] = _reg >> 8; /* 寄存器地址 高字节 */
Tx_Buf[TxCount++] = _reg; /* 寄存器地址 低字节 */
Tx_Buf[TxCount++] = _num >> 8; /* 开关(Input)个数 高字节 */
Tx_Buf[TxCount++] = _num; /* 开关(Input)个数 低字节 */
crc = MB_CRC16(Tx_Buf, TxCount);
Tx_Buf[TxCount++] = crc; /* crc 低字节 */
Tx_Buf[TxCount++] = crc >> 8; /* crc 高字节 */
*TxCount_t = TxCount;
//UART_Tx((uint8_t *)&Tx_Buf,TxCount);
//uartHandler->UART_Tx(uartHandler,(uint8_t *)&Tx_Buf,TxCount);
}
/**
* : (HoldingRegister)
* : _addr:,_reg:,_num:
* :
* : ,
*/
void MB_ReadHoldingReg(uint8_t *Tx_Buf, uint8_t *TxCount_t, uint8_t _addr,
uint16_t _reg, uint16_t _num)
{
MB_rx_flag = 2;
Read_Reg_Num = _num;
Read_Slave_ID = _addr;
uint16_t TxCount = 0;
uint16_t crc = 0;
Tx_Buf[TxCount++] = _addr; /* 从站地址 */
Tx_Buf[TxCount++] = 0x03; /* 功能码 */
Tx_Buf[TxCount++] = _reg >> 8; /* 寄存器地址 高字节 */
Tx_Buf[TxCount++] = _reg; /* 寄存器地址 低字节 */
Tx_Buf[TxCount++] = _num >> 8; /* 寄存器(16bits)个数 高字节 */
Tx_Buf[TxCount++] = _num; /* 低字节 */
crc = MB_CRC16(Tx_Buf, TxCount);
Tx_Buf[TxCount++] = crc; /* crc 低字节 */
Tx_Buf[TxCount++] = crc >> 8; /* crc 高字节 */
*TxCount_t = TxCount;
//UART_Tx((uint8_t *)&Tx_Buf,TxCount);
//uartHandler->UART_Tx(uartHandler,(uint8_t *)&Tx_Buf,TxCount);
}
/**
* : N个输入寄存器(InputRegister)
* : _addr:,_reg:,_num:
* :
* : ,.
*/
void MB_ReadInputReg(uint8_t *Tx_Buf, uint8_t *TxCount_t, uint8_t _addr,
uint16_t _reg, uint16_t _num)
{
uint16_t TxCount = 0;
uint16_t crc = 0;
Tx_Buf[TxCount++] = _addr; /* 从站地址 */
Tx_Buf[TxCount++] = 0x04; /* 功能码 */
Tx_Buf[TxCount++] = _reg >> 8; /* 寄存器地址 高字节 */
Tx_Buf[TxCount++] = _reg; /* 寄存器地址 低字节 */
Tx_Buf[TxCount++] = _num >> 8; /* 寄存器(16bits)个数 高字节 */
Tx_Buf[TxCount++] = _num; /* 低字节 */
crc = MB_CRC16(Tx_Buf, TxCount);
Tx_Buf[TxCount++] = crc; /* crc 低字节 */
Tx_Buf[TxCount++] = crc >> 8; /* crc 高字节 */
*TxCount_t = TxCount;
//UART_Tx((uint8_t *)&Tx_Buf,TxCount);
}
/**
* : (HoldingRegister)
* : _addr:,_reg:,_data:
* :
* : ,
*/
void MB_WriteHoldingReg(uint8_t *Tx_Buf, uint8_t *TxCount_t, uint8_t _addr,
uint16_t _reg, uint16_t _data)
{
uint16_t TxCount = 0;
uint16_t crc = 0;
Tx_Buf[TxCount++] = _addr; /* 从站地址 */
Tx_Buf[TxCount++] = 0x06; /* 功能码 */
Tx_Buf[TxCount++] = _reg >> 8; /* 寄存器地址 高字节 */
Tx_Buf[TxCount++] = _reg; /* 寄存器地址 低字节 */
Tx_Buf[TxCount++] = _data >> 8; /* 寄存器(16bits)个数 高字节 */
Tx_Buf[TxCount++] = _data; /* 低字节 */
crc = MB_CRC16(Tx_Buf, TxCount);
Tx_Buf[TxCount++] = crc; /* crc 低字节 */
Tx_Buf[TxCount++] = crc >> 8; /* crc 高字节 */
*TxCount_t = TxCount;
//UART_Tx((uint8_t *)&Tx_Buf,TxCount);
//uartHandler->UART_Tx(uartHandler,(uint8_t *)&Tx_Buf,TxCount);
}
/**
* : N个保持寄存器(HoldingRegister)
* : _addr:,_reg:,_num:,_databuf:
* :
* : ,._databuf的长度需 >= _num*2
*/
void MB_WriteNumHoldingReg(uint8_t *Tx_Buf, uint8_t *TxCount_t, uint8_t _addr,
uint16_t _reg, uint16_t _num, uint8_t *_databuf)
{
uint16_t i;
uint16_t TxCount = 0;
uint16_t crc = 0;
Tx_Buf[TxCount++] = _addr; /* 从站地址 */
Tx_Buf[TxCount++] = 0x10; /* 功能码 */
Tx_Buf[TxCount++] = _reg >> 8; /* 寄存器地址 高字节 */
Tx_Buf[TxCount++] = _reg; /* 寄存器地址 低字节 */
Tx_Buf[TxCount++] = _num >> 8; /* 寄存器(16bits)个数 高字节 */
Tx_Buf[TxCount++] = _num; /* 低字节 */
Tx_Buf[TxCount++] = _num << 1; /* 数据个数 */
for (i = 0; i < 2 * _num; i++)
{
Tx_Buf[TxCount++] = _databuf[i]; /* 后面的数据长度 */
}
crc = MB_CRC16(Tx_Buf, TxCount);
Tx_Buf[TxCount++] = crc; /* crc 低字节 */
Tx_Buf[TxCount++] = crc >> 8; /* crc 高字节 */
//UART_Tx((uint8_t *)&Tx_Buf,TxCount);
*TxCount_t = TxCount;
}
/**
* : Read_Reg_Num个保持寄存器的值 (HoldingRegister)
* : buffer:,length:, Read_Reg_Num , Decoded_Reg_Value 16
* : 1 0 CRC验证错误
* :
*/
uint8_t MB_Decode_HoldingRegs(uint8_t buffer[], uint16_t length,uint16_t Read_Reg_Num,uint16_t* Decoded_Reg_Value)
{
/* CRC 校验 */
uint16_t crc_check = ((buffer[length - 1] << 8) | buffer[length - 2]);
/* CRC 校验正确 */
if (crc_check == MB_CRC16(buffer, length - 2))
{
int i = 0;
for (i = 0; i < Read_Reg_Num; i++)
{
Decoded_Reg_Value[ i] =
(buffer[3 + 2 * i] << 8) + buffer[4 + 2 * i];
}
return 1; //Decoded successfully
}
else
{
return 0; //Decode Error;
}
}
uint8_t MB_Decode_InputRegs(uint8_t buffer[], uint16_t length,uint16_t Read_Reg_Num,uint16_t* Decoded_Reg_Value)
{
/* CRC 校验 */
uint16_t crc_check = ((buffer[length - 1] << 8) | buffer[length - 2]);
/* CRC 校验正确 */
if (crc_check == MB_CRC16(buffer, length - 2))
{
int i = 0;
for (i = 0; i < Read_Reg_Num; i++)
{
Decoded_Reg_Value[ i] =
(buffer[3 + 2 * i] << 8) + buffer[4 + 2 * i];
}
return 1; //Decoded successfully
}
else
{
return 0; //Decode Error;
}
}

20
Bingoo/base/bsp_PID.pb.c

@ -0,0 +1,20 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_PID.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(PID_Parameters, PID_Parameters, AUTO)
#ifndef PB_CONVERT_DOUBLE_FLOAT
/* On some platforms (such as AVR), double is really float.
* To be able to encode/decode double on these platforms, you need.
* to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line.
*/
PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES)
#endif

12
Bingoo/base/bsp_PV.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_PV.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(PV_struct_define, PV_struct_define, AUTO)

12
Bingoo/base/bsp_ReCmd.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_ReCmd.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(ReCmd, ReCmd, 2)

186
Bingoo/base/bsp_TCPClient.c

@ -0,0 +1,186 @@
#include "BSP/bsp_TCPClient.h"
#include "lwip/netif.h"
#include "lwip/ip.h"
#include "lwip/tcp.h"
#include "lwip/init.h"
#include "netif/etharp.h"
#include "lwip/udp.h"
#include "lwip/pbuf.h"
#include <stdio.h>
#include <string.h>
#include "BHBF_ROBOT.h"
#pragma pack (1) /*指定按1字节对齐*/
#pragma pack () /*取消指定对齐,恢复缺省对齐*/
LazorData *ReadLazorData;
unsigned char *Weld_Out_Flag;
unsigned char Weld_Out_Count;
unsigned char Weld_Out_SafeCount = 500;
uint8_t ReceivedData[3000];
static uint16_t receivedLength = 0;
void IntiazlieLazor();
void IntiazlieLazor1();
static err_t client_connected(void *arg, struct tcp_pcb *pcb, err_t err);
ip4_addr_t server_ip;
static struct tcp_pcb *client_pcb = NULL;
static void client_err(void *arg, err_t err)
{
//printf("connect error! closed by core!!\n");
//printf("try to connect to server again!!\n");
//连接失败的时候释放TCP控制块的内存
tcp_close(client_pcb);
//重新连接
TCP_Client_Init();
}
int index_0 = 0;
int count_Client;
static err_t client_send(void *arg, struct tcp_pcb *tpcb)
{
// count_Client++;
// if(count_Client >= 50)
// {
// count_Client = 49;
switch (index_0)
{
case 0:case 1:
{
uint8_t send_buf[] =
{0x00,0x15,0x00,0x00,0x00,0x1B,0x01,0x10,0x03,0xE8,0x00,0x0A,0x14,
0x0D,0x0C,0x0B,0x0A,0x00,0x00,0x08,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00};
tcp_write(tpcb, send_buf, sizeof(send_buf), 1);
tcp_output(client_pcb);
index_0++;
break;
}
case 2:case 3:
{
uint8_t send_buf[] =
{0x00,0x15,0x00,0x00,0x00,0x1B,0x01,0x10,0x03,0xE8,0x00,0x0A,0x14,
0x0D,0x0C,0x0B,0x0A,0x00,0x00,0x01,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00};
tcp_write(tpcb, send_buf, sizeof(send_buf), 1);
tcp_output(client_pcb);
index_0++;
break;
}
case 4:
{
uint8_t send_buf[] =
{0x00,0x05,0x00,0x00,0x00,0x06,0x01,0x03,0x07,0xD0,0x00,0x12};
tcp_write(tpcb, send_buf, sizeof(send_buf), 1);
tcp_output(client_pcb);
break;
}
// case 0:case 1:
// {
// uint8_t send_buf[4] =
// { 0x01, 0x00, 0x00, 0x00 };
// tcp_write(tpcb, send_buf, sizeof(send_buf), 1);
// tcp_output(client_pcb);
// index_0++;
// break;
// }
//
// case 2:case 3:
// {
// uint8_t send_buf[4] =
// { 0x08, 0x00, 0x04, 0x00 };
// tcp_write(tpcb, send_buf, sizeof(send_buf), 1);
// tcp_output(client_pcb);
// index_0++;
// break;
// }
}
// }
return ERR_OK;
}
static err_t client_recv(void *arg, struct tcp_pcb *tpcb, struct pbuf *p,
err_t err)
{
if (p != NULL)
{
/* 接收数据*/
/* 返回接收到的数据*/
//tcp_write(tpcb, p->payload, p->tot_len, 1);
receivedLength = p->tot_len;
// if (p->tot_len == 36)
// {
memcpy(ReceivedData, p->payload, p->tot_len);
// }
//memset(p->payload, 0, p->tot_len);
tcp_recved(tpcb, p->tot_len);
pbuf_free(p);
} else if (err == ERR_OK)
{
//服务器断开连接
//printf("server has been disconnected!\n");
tcp_close(tpcb);
//重新连接
TCP_Client_Init();
// tcp_connect(client_pcb, &server_ip, TCP_CLIENT_PORT, client_connected);
}
return ERR_OK;
}
static err_t client_connected(void *arg, struct tcp_pcb *pcb, err_t err)
{
// printf("connected ok!\n");
//注册一个周期性回调函数
tcp_poll(pcb, client_send, 1);
//注册一个接收函数
tcp_recv(pcb, client_recv); //TCP_TMR_INTERVAL == 50 在tcp_priv.h
return ERR_OK;
}
void TCP_Client_Init(void)
{
ReadLazorData = &ReceivedData[25];
Weld_Out_Flag = &ReceivedData[11];
/* 创建一个TCP控制块 */
client_pcb = tcp_new();
client_pcb->flags |= TF_NODELAY;
IP4_ADDR(&server_ip, DEST_IP_ADDR0, DEST_IP_ADDR1, DEST_IP_ADDR2,
DEST_IP_ADDR3);
//printf("client start connect!\n");
//开始连接
tcp_connect(client_pcb, &server_ip, DEST_PORT, client_connected);
//注册异常处理
tcp_err(client_pcb, client_err);
}

71
Bingoo/base/bsp_TIMER.c

@ -0,0 +1,71 @@
/*
* bsp_TIMER.c
*
* Created on: Oct 26, 2023
* Author: shiya
*/
#include "BSP/bsp_TIMER.h"
#include "lwip.h"
#include "BSP/bsp_mqtt.h"
//返回值::1-正常;0-错误
uint8_t GF_BSP_TIMER_Init()
{
HAL_TIM_Base_Start_IT(&htim1);
HAL_TIM_Base_Start_IT(&htim8);
return 1;
}
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
{
//100ms - WatchDog
if(htim->Instance == TIM1)//APB2=200Mhz,htim1.Init.Prescaler = 2000-1;htim1.Init.Period = 10000-1; TIM1=100ms
{
GF_BSP_Interrupt_Run_CallBack(DF_BSP_InterCall_TIM1_100ms_PeriodElapsedCallback);
}
//2ms - MainLoop
if(htim->Instance == TIM8)//APB2=200Mhz,htim8.Init.Prescaler = 2000-1;htim8.Init.Period = 200-1; TIM8=2ms
{
MX_LWIP_Process();
GF_BSP_Interrupt_Run_CallBack(DF_BSP_InterCall_TIM8_2ms_PeriodElapsedCallback);
//bsp_mqtt_test();
}
}
void GF_BSP_TIMER_DelayUS(uint32_t n)
{
uint32_t ticks;
uint32_t told;
uint32_t tnow;
uint32_t tcnt = 0;
uint32_t reload;
reload = SysTick->LOAD;
ticks = n * (SystemCoreClock / 1000000);
tcnt = 0;
told = SysTick->VAL;
while (1)
{
tnow = SysTick->VAL;
if (tnow != told)
{
if (tnow < told)
{
tcnt += told - tnow;
}
else
{
tcnt += reload - tnow + told;
}
told = tnow;
if (tcnt >= ticks)
{
break;
}
}
}
}

553
Bingoo/base/bsp_UART.c

@ -0,0 +1,553 @@
#include "BSP/bsp_UART.h"
#include "main.h"
#include <stdlib.h>
void GF_UART_Send_List_Send(struct UARTHandler *handler);
void Dispatcher_List_Add(struct UARTHandler *uartHandler,
void (*dispache)(void));
void UARTHandlerAddTxList(struct UARTHandler *uartHandler, uint8_t *data,
uint16_t length, uint32_t txListTimePeriod, void (*UART_Decode)(uint8_t*, uint16_t));
//Store all the data in these buffer
uint8_t RS485_1_RxMA_buf[UART_Receive_MAX_NUM];
uint8_t RS485_2_RxDMA_buf[UART_Receive_MAX_NUM];
uint8_t RS485_3_RxDMA_buf[UART_Receive_MAX_NUM];
uint8_t RS485_4_RxDMA_buf[UART_Receive_MAX_NUM];
uint8_t Debug_RxDMA_buf[UART_Receive_MAX_NUM];
uint8_t ExternSerial_RxDMA_buf[UART_Receive_MAX_NUM];
uint8_t RS485_1_TxDMA_buf[UART_Transmit_MAX_NUM];
uint8_t RS485_2_TxDMA_buf[UART_Transmit_MAX_NUM];
uint8_t RS485_3_TxDMA_buf[UART_Transmit_MAX_NUM];
uint8_t RS485_4_TxDMA_buf[UART_Transmit_MAX_NUM];
uint8_t Debug_TxDMA_buf[UART_Transmit_MAX_NUM];
uint8_t ExternSerial_TxDMA_buf[UART_Transmit_MAX_NUM];
#define InterCall_DEBUG_UART huart4
#define E28_SBUS_UART huart5
#define RS485_4_UART huart7
#define RS485_1_UART huart1
#define LTE_7S0_Serial_UART huart2
#define RS485_2_UART huart3
#define RS485_3_UART huart6
struct UARTHandler RS_485_1_UART_Handler;
struct UARTHandler RS_485_2_UART_Handler;
struct UARTHandler RS_485_3_UART_Handler;
struct UARTHandler RS_485_4_UART_Handler;
struct UARTHandler InterCall_DEBUG_UART_Handler;
struct UARTHandler E28_SBUS_UART_Handler;
struct UARTHandler LTE_7S0_Serial_UART_Handler;
#if defined (hlpuart1Exit)
#define LPUART1UART hlpuart1
struct UARTHandler LPUART1_UART_Handler;
#endif
void GF_BSP_UARTHandlers_Intialize(
int32_t RS485_1_WaitTime,
int32_t RS485_2_WaitTime,
int32_t RS485_3_WaitTime,
int32_t RS485_4_WaitTime,
int32_t LTE_7S0_Serial_WaitTime,
int32_t InterCall_DEBUG_WaitTime,
int32_t E28_SBUS_WaitTime,
int32_t LPUART1_UART_WaitTime,
int32_t RS485_1_Dispacher_Time,
int32_t RS485_2_Dispacher_Time,
int32_t RS485_3_Dispacher_Time,
int32_t RS485_4_Dispacher_Time,
int32_t LTE_7S0_Serial_Dispacher_Time,
int32_t InterCall_DEBUG_Dispacher_Time,
int32_t E28_SBUS_Dispacher_Time,
int32_t LPUART1_UART_Dispacher_Time
)
{
IntializeUARTHandler(&RS_485_1_UART_Handler, &RS485_1_UART, RS485_1_WaitTime, 2,RS485_1_Dispacher_Time);
IntializeUARTHandler(&RS_485_2_UART_Handler, &RS485_2_UART, RS485_2_WaitTime, 2,RS485_2_Dispacher_Time);
IntializeUARTHandler(&RS_485_3_UART_Handler, &RS485_3_UART, RS485_3_WaitTime, 2,RS485_3_Dispacher_Time);
IntializeUARTHandler(&RS_485_4_UART_Handler, &RS485_4_UART, RS485_4_WaitTime, 2,RS485_4_Dispacher_Time);
IntializeUARTHandler(&LTE_7S0_Serial_UART_Handler, &LTE_7S0_Serial_UART, LTE_7S0_Serial_WaitTime, 2,LTE_7S0_Serial_Dispacher_Time);
IntializeUARTHandler(&InterCall_DEBUG_UART_Handler, &InterCall_DEBUG_UART, InterCall_DEBUG_WaitTime, 2,InterCall_DEBUG_Dispacher_Time);
IntializeUARTHandler(&E28_SBUS_UART_Handler, &E28_SBUS_UART, E28_SBUS_WaitTime, 2,E28_SBUS_Dispacher_Time);
HAL_UART_Receive_IT((E28_SBUS_UART_Handler.uart),
(uint8_t*) &E28_SBUS_UART_Handler.tmp_Rx_Buf, 1);
HAL_UART_Receive_IT((InterCall_DEBUG_UART_Handler.uart),
(uint8_t*) &InterCall_DEBUG_UART_Handler.tmp_Rx_Buf, 1);
HAL_UART_Receive_IT((RS_485_1_UART_Handler.uart),
(uint8_t*) &RS_485_1_UART_Handler.tmp_Rx_Buf, 1);
HAL_UART_Receive_IT((RS_485_2_UART_Handler.uart),
(uint8_t*) &RS_485_2_UART_Handler.tmp_Rx_Buf, 1);
HAL_UART_Receive_IT((RS_485_3_UART_Handler.uart),
(uint8_t*) &RS_485_3_UART_Handler.tmp_Rx_Buf, 1);
HAL_UART_Receive_IT((RS_485_4_UART_Handler.uart),
(uint8_t*) &RS_485_4_UART_Handler.tmp_Rx_Buf, 1);
HAL_UART_Receive_IT((LTE_7S0_Serial_UART_Handler.uart),
(uint8_t*) &LTE_7S0_Serial_UART_Handler.tmp_Rx_Buf, 1);
#if defined (hlpuart1Exit)
IntializeUARTHandler(&LPUART1_UART_Handler, &LPUART1UART, LPUART1_UART_WaitTime, 2,LPUART1_UART_Dispacher_Time); //10ms 剩余2ms
HAL_UART_Receive_IT((LPUART1_UART_Handler.uart),
(uint8_t*) &LPUART1_UART_Handler.tmp_Rx_Buf, 1);
#endif
GF_BSP_Interrupt_Add_CallBack(
DF_BSP_InterCall_TIM8_2ms_PeriodElapsedCallback, GF_BSP_UART_Timer);
//RS_485_2_UART_Handler.send_finished=1;
}
//Count Every 2 ms
void GF_BSP_UART_Timer()
{
Counting(&RS_485_1_UART_Handler);
Counting(&RS_485_2_UART_Handler);
Counting(&RS_485_3_UART_Handler);
Counting(&RS_485_4_UART_Handler);
Counting(&LTE_7S0_Serial_UART_Handler);
Counting(&InterCall_DEBUG_UART_Handler);
Counting(&E28_SBUS_UART_Handler);
#if defined (hlpuart1Exit)
Counting(&LPUART1_UART_Handler);
#endif
}
void UARTHandlerAddTxList(struct UARTHandler *uartHandler, uint8_t *data,
uint16_t length, uint32_t txListTimePeriod, void (*UART_Decode)(uint8_t*, uint16_t))
{
UARTSendHandler *pTmp = NULL; //临时指针
//临时指针2用于逐个申请内存
pTmp = (UARTSendHandler*) malloc(sizeof(UARTSendHandler));
memcpy(pTmp->Tx_Buf, data, length);
pTmp->pNext = NULL;
pTmp->SendListTimePeriod=txListTimePeriod;
pTmp->SendLength = length;
pTmp->UART_Decode = UART_Decode;
//if NULL, call intialize one
if (uartHandler->pCurrentUARTSendHadler == NULL)
{
uartHandler->pCurrentUARTSendHadler = pTmp; //空链表
} else
{
char i = 0;
//插到尾部
UARTSendHandler *phead = NULL;
phead = uartHandler->pCurrentUARTSendHadler;
while (phead->pNext != NULL)
{
i++;
phead = phead->pNext;
}
phead->pNext = pTmp;
}
}
void UARTHandlerTx(struct UARTHandler *uartHandler)
{
if (uartHandler->uart == NULL)
{
LOGFF(DL_ERROR,
"the UART Hardware did not intialize,check the setting");
return;
}
uartHandler->RxCount=0;//设定RxCount为0
#if defined (hlpuart1Exit)
if(uartHandler->uart->Instance == LPUART1)
{
HAL_UART_Transmit(uartHandler->uart, uartHandler->Tx_Buf,
uartHandler->TxCount,100);
}else
{
#endif
if (uartHandler->uart->Instance == UART4) //**DEBUG
{
} else if (uartHandler->uart->Instance == USART1) //**RS485_1
{
HAL_GPIO_WritePin(RS485_1_DIR_GPIO_Port, RS485_1_DIR_Pin, GPIO_PIN_SET);
} else if (uartHandler->uart->Instance == USART3) //**RS485_2
{
HAL_GPIO_WritePin(RS485_2_DIR_GPIO_Port, RS485_2_DIR_Pin, GPIO_PIN_SET);
} else if (uartHandler->uart->Instance == USART6) //**RS485_3
{
HAL_GPIO_WritePin(RS485_3_DIR_GPIO_Port, RS485_3_DIR_Pin, GPIO_PIN_SET);
} else if (uartHandler->uart->Instance == UART7) //**RS485_4
{
HAL_GPIO_WritePin(RS485_4_DIR_GPIO_Port, RS485_4_DIR_Pin, GPIO_PIN_SET);
} else if (uartHandler->uart->Instance == USART2)//**E22 // External serial port
{
} else if (uartHandler->uart->Instance == UART5) //**E28 // SBUS
{
}
SCB_CleanInvalidateDCache_by_Addr((uint32_t*) uartHandler->Tx_Buf,
uartHandler->TxCount);
HAL_UART_Transmit_DMA(uartHandler->uart, uartHandler->Tx_Buf,
uartHandler->TxCount);
#if defined (hlpuart1Exit)
}
#endif
if (uartHandler->uart == UART4) //**DEBUG
{
} else if (uartHandler->uart == USART1) //**RS485_1
{
HAL_GPIO_WritePin(RS485_1_DIR_GPIO_Port, RS485_1_DIR_Pin,
GPIO_PIN_RESET);
} else if (uartHandler->uart == USART3) //**RS485_2
{
HAL_GPIO_WritePin(RS485_2_DIR_GPIO_Port, RS485_2_DIR_Pin,
GPIO_PIN_RESET);
} else if (uartHandler->uart == USART6) //**RS485_3
{
HAL_GPIO_WritePin(RS485_3_DIR_GPIO_Port,
RS485_3_DIR_Pin, GPIO_PIN_RESET);
} else if (uartHandler->uart == UART7) //**RS485_4
{
HAL_GPIO_WritePin(RS485_4_DIR_GPIO_Port,
RS485_4_DIR_Pin, GPIO_PIN_RESET);
} else if (uartHandler->uart == USART2) //**E22 // External serial port
{
} else if (uartHandler->uart == UART5) //**E28 // SBUS
{
}
}
void UARTHandlerRX(struct UARTHandler *uartHandler)
{
//uartHandler->Wait_Time_Count = 0;
if (uartHandler->startCountFlag == 0)
{
uartHandler->startCountFlag = 1;
uartHandler->RxCount = 0;
}
uartHandler->Rx_Buf[uartHandler->RxCount] = uartHandler->tmp_Rx_Buf[0];
uartHandler->RxCount++;
HAL_UART_Receive_IT(uartHandler->uart, uartHandler->tmp_Rx_Buf, 1);
uartHandler->Wait_Time_Count = 0;
if(uartHandler->RxCount>=1024)//接收数据过多,直接抛弃
{
uartHandler->RxCount=0;
}
//HAL_UART_Receive_IT(uartHandler->uart, RS_485_2_UART_Handler.tmp_Rx_Buf, 1);
}
void IntializeUARTHandler(struct UARTHandler *uartHandler,
UART_HandleTypeDef *uart, int32_t WaitTime, unsigned char timeSpan,int32_t Dispacher_Time)
{
uartHandler->Wait_Time_Count = 0;
uartHandler->Wait_time = WaitTime;
uartHandler->uart = uart;
uartHandler->UART_Rx = UARTHandlerRX;
uartHandler->UART_Tx = UARTHandlerTx;
uartHandler->AddSendList = UARTHandlerAddTxList;
uartHandler->dispacherController = (DispacherController*) malloc(
sizeof(DispacherController));
uartHandler->dispacherController->pHead = NULL;
uartHandler->dispacherController->pTail = NULL;
uartHandler->dispacherController->Dispacher_Enable = 0;
uartHandler->dispacherController->DispacherCallTime = Dispacher_Time ; // call the function every 50 ms
uartHandler->dispacherController->Dispacher_Counter = 0;
uartHandler->dispacherController->DispacherNumber = 0;
uartHandler->dispacherController->Add_Dispatcher_List = Dispatcher_List_Add_t;
uartHandler->dispacherController->Dispatcher_Run = Dispatch_t;
uartHandler->timeSpan = 2;
uartHandler->SendList_time_Count = 0;
uartHandler->SendList_Period = 100;
}
void Counting(struct UARTHandler *uartHandler)
{
if (uartHandler->UART_Decode == NULL) //不解析,直接返回true
{
uartHandler->decode_finished = 1;
} else
{
if (uartHandler->startCountFlag == 1)
{
uartHandler->Wait_Time_Count++;
if (uartHandler->timeSpan * uartHandler->Wait_Time_Count
>= uartHandler->Wait_time)
{
uartHandler->Wait_Time_Count = 0;
uartHandler->startCountFlag = 0;
//启动解析函数
if (uartHandler->RxCount >= 1)
{
if(uartHandler->UART_Decode!=NULL)
{
uartHandler->UART_Decode(uartHandler->Rx_Buf,
uartHandler->RxCount);
}
uartHandler->RxCount = 0;
}
}
}
}
if (uartHandler->pCurrentUARTSendHadler != NULL)
{
GF_UART_Send_List_Send(uartHandler);
} else
{
uartHandler->dispacherController->Dispatcher_Run(
uartHandler->dispacherController);
}
}
//_weak
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart)
{
if (huart->Instance == UART4) //**DEBUG
{
UARTHandlerRX(&InterCall_DEBUG_UART_Handler);
//GF_BSP_Interrupt_Run_CallBack(DF_BSP_InterCall_DEBUG_RxCpltCallback);
} else if (huart->Instance == USART1) //**RS485_1
{
//GF_BSP_Interrupt_Run_CallBack(DF_BSP_InterCall_RS485_1_RxCpltCallback);
UARTHandlerRX(&RS_485_1_UART_Handler);
} else if (huart->Instance == USART3) //**RS485_2
{
//GF_BSP_Interrupt_Run_CallBack(DF_BSP_InterCall_RS485_2_RxCpltCallback);
UARTHandlerRX(&RS_485_2_UART_Handler);
} else if (huart->Instance == USART6) //**RS485_3
{
//GF_BSP_Interrupt_Run_CallBack(DF_BSP_InterCall_RS485_3_RxCpltCallback);
UARTHandlerRX(&RS_485_3_UART_Handler);
} else if (huart->Instance == UART7) //**RS485_4
{
// UARTHandlerRX(&RS_485_4_UART_Handler);
//GF_BSP_Interrupt_Run_CallBack(DF_BSP_InterCall_RS485_4_RxCpltCallback);
UARTHandlerRX(&RS_485_4_UART_Handler);
} else if (huart->Instance == USART2) //**E22 // External serial port
{
// GF_BSP_Interrupt_Run_CallBack(
// DF_BSP_InterCall_E22_Serial_RxCpltCallback);
UARTHandlerRX(&LTE_7S0_Serial_UART_Handler);
} else if (huart->Instance == UART5) //**E28 // SBUS
{
// GF_BSP_Interrupt_Run_CallBack(
// DF_BSP_InterCall_E28_SBUS_RxFifo0Callback);
UARTHandlerRX(&E28_SBUS_UART_Handler);
}
#if defined (hlpuart1Exit)
else if (huart->Instance == LPUART1) //**E28 // SBUS
{
UARTHandlerRX(&LPUART1_UART_Handler);
}
#endif
}
void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart)
{
if (huart->Instance == UART4) //**DEBUG
{
} else if (huart->Instance == USART1) //**RS485_1
{
HAL_GPIO_WritePin(RS485_1_DIR_GPIO_Port, RS485_1_DIR_Pin,
GPIO_PIN_RESET);
} else if (huart->Instance == USART3) //**RS485_2
{
HAL_GPIO_WritePin(RS485_2_DIR_GPIO_Port, RS485_2_DIR_Pin,
GPIO_PIN_RESET);
} else if (huart->Instance == USART6) //**RS485_3
{
HAL_GPIO_WritePin(RS485_3_DIR_GPIO_Port,
RS485_3_DIR_Pin, GPIO_PIN_RESET);
} else if (huart->Instance == UART7) //**RS485_4
{
HAL_GPIO_WritePin(RS485_4_DIR_GPIO_Port,
RS485_4_DIR_Pin, GPIO_PIN_RESET);
} else if (huart->Instance == USART2) //**E22 // External serial port
{
} else if (huart->Instance == UART5) //**E28 // SBUS
{
}
}
//RS485_Index:1-4 RS485; 5 ExternSerial; 6 Debug;
void GF_BSP_UART_Transmit(const uint8_t RS485_Index, const uint8_t *pData,
uint16_t Size)
{
UART_HandleTypeDef *huart;
if (Size > UART_Transmit_MAX_NUM)
Size = UART_Transmit_MAX_NUM;
switch (RS485_Index)
{
case 1:
huart = &huart1;
HAL_GPIO_WritePin(RS485_1_DIR_GPIO_Port, RS485_1_DIR_Pin,
GPIO_PIN_SET);
memcpy(RS485_1_TxDMA_buf, pData, Size);
SCB_CleanInvalidateDCache_by_Addr((uint32_t*) RS485_1_TxDMA_buf,
Size);
HAL_UART_Transmit_DMA(huart, RS485_1_TxDMA_buf, Size);
//HAL_UART_Transmit(&huart1, (uint8_t *)&ch, 1, 0xffff);
break;
case 2:
huart = &huart3;
HAL_GPIO_WritePin(RS485_2_DIR_GPIO_Port, RS485_2_DIR_Pin,
GPIO_PIN_SET);
memcpy(RS485_2_TxDMA_buf, pData, Size);
SCB_CleanInvalidateDCache_by_Addr((uint32_t*) RS485_2_TxDMA_buf,
Size);
HAL_UART_Transmit_DMA(huart, RS485_2_TxDMA_buf, Size);
break;
case 3:
huart = &huart6;
HAL_GPIO_WritePin(RS485_3_DIR_GPIO_Port, RS485_3_DIR_Pin,
GPIO_PIN_SET);
memcpy(RS485_3_TxDMA_buf, pData, Size);
SCB_CleanInvalidateDCache_by_Addr((uint32_t*) RS485_3_TxDMA_buf,
Size);
HAL_UART_Transmit_DMA(huart, RS485_3_TxDMA_buf, Size);
break;
case 4:
huart = &huart7;
HAL_GPIO_WritePin(RS485_4_DIR_GPIO_Port, RS485_4_DIR_Pin,
GPIO_PIN_SET);
memcpy(RS485_4_TxDMA_buf, pData, Size);
SCB_CleanInvalidateDCache_by_Addr((uint32_t*) RS485_4_TxDMA_buf,
Size);
HAL_UART_Transmit_DMA(huart, RS485_4_TxDMA_buf, Size);
break;
case 5:
huart = &huart2;
memcpy(ExternSerial_TxDMA_buf, pData, Size);
SCB_CleanInvalidateDCache_by_Addr(
(uint32_t*) ExternSerial_TxDMA_buf, Size);
HAL_UART_Transmit_DMA(huart, ExternSerial_TxDMA_buf, Size);
break;
default:
huart = &huart4;
memcpy(Debug_TxDMA_buf, pData, Size);
SCB_CleanInvalidateDCache_by_Addr((uint32_t*) Debug_TxDMA_buf,
Size);
HAL_UART_Transmit_DMA(huart, Debug_TxDMA_buf, Size);
break;
}
}
void GF_UART_Send_List_Send(struct UARTHandler *handler)
{
handler->SendList_time_Count++;
if (handler->timeSpan * handler->SendList_time_Count
>= handler->SendList_Period)
{
handler->SendList_time_Count = 0;
handler->SendListExists = 1;
if (handler->pCurrentUARTSendHadler != NULL)
{
//拷贝数据到相关的代码中,然后发送
//handler->CAN_Decode = handler->pCurrentCANSendHadler->CAN_Decode; //
memcpy(handler->Tx_Buf, handler->pCurrentUARTSendHadler->Tx_Buf,
handler->pCurrentUARTSendHadler->SendLength);
handler->SendList_Period =
handler->pCurrentUARTSendHadler->SendListTimePeriod;
handler->TxCount = handler->pCurrentUARTSendHadler->SendLength;
//添加了新的UARTDecode代码,需要做测试,适合一个485线上挂至少2个设备
handler->UART_Tx(handler);
handler->UART_Decode=handler->pCurrentUARTSendHadler->UART_Decode;
//计数重新开始
//handler->RxCount=0;
if (handler->pCurrentUARTSendHadler->pNext != NULL)
{
UARTSendHandler *temp = handler->pCurrentUARTSendHadler->pNext;
free(handler->pCurrentUARTSendHadler); //清除内存
handler->pCurrentUARTSendHadler = temp;
} else
{
free(handler->pCurrentUARTSendHadler); //清除内存
handler->pCurrentUARTSendHadler = NULL;
}
} else
{
handler->SendListExists = 0;
}
}
}

430
Bingoo/base/bsp_UDP.c

@ -0,0 +1,430 @@
/*
* bsp_UDP.c
*
* Created on: Aug 13, 2024
* Author: akeguo
*/
#include "stm32h7xx_hal.h"
#include "lwip.h"
#include "udp.h"
#include "string.h"
#include "bsp_UDP.h"
#include "bsp_DLT_Log.h"
#include <bsp_UpperComputer_Handler.h>
#include "BSP/bsp_GPIO.h"
void UDP_GV_Dispatch();
void UDP_IV_Dispatch();
void udp_cmd_send_GV(char *pData, uint16_t Size);
/* 定义端口号 */
#define UDP_DLT_LOCAL_PORT 8000 /* 本地端口 */
#define UDP_CMD_LOCAL_PORT 8002 /* 本地端口 */
#define UDP_CMD_LOCAL_Android_Listen_PORT 8006 /* 本地端口 接收安卓 */
#define UDP_DLT_Send_LOCAL_PORT 7000 /* 本地端口 */
#define UDP_CMD_Send_LOCAL_PORT 7002 /* 本地端口 */
#define UDP_GV_Send_LOCAL_PORT 7004 /* 本地端口 */
#define UDP_Android_Send_LOCAL_PORT 7006 /* 本地端口 发给安卓*/
/*32从7006发往安卓9006*/
/*安卓从9006发往32的8006*/
#define UDP_REMOTE_DLT_PORT 9000 /* 远端端口 */
#define UDP_REMOTE_CMD_PORT 9002 /* 远端端口 */
#define UDP_REMOTE_GV_PORT 9004 /* 远端端口 */
#define UDP_REMOTE_Android_PORT 9006 /* 远端端口 */
int8_t is_udp_GV_update_loop_enalbed = 0;
unsigned char received_data[1000];
/* udp控制块 */
static struct udp_pcb *upcb_Rx_DLT;
static struct udp_pcb *upcb_Rx_Cmd;
static struct udp_pcb *upcb_Rx_From_Android;
static struct udp_pcb *upcb_Tx_DLT;
static struct udp_pcb *upcb_Tx_Cmd;
static struct udp_pcb *upcb_Tx_GV;
static struct udp_pcb *upcb_Tx_Android;
ip_addr_t serverIP;
ip_addr_t Android_ServerIP;
DLT_DecodeFuncPtr UDP_DLT_ReceivedCallback;
/******************************************************************************
* :
* : -
* :
******************************************************************************/
static void udp_receive_callback(void *arg, struct udp_pcb *upcb,
struct pbuf *p, const ip_addr_t *addr, u16_t port)
{
if (p == NULL) return;
memcpy(received_data, p->payload, p->len);
if (upcb->local_port == UDP_DLT_LOCAL_PORT)
{
UDP_DLT_ReceivedCallback(received_data, p->len);
//DLT_DataReceiveEndCallback(received_data, p->len);
}
else if (upcb->local_port == UDP_CMD_LOCAL_PORT)
{
if (*received_data == 0x55 && *(received_data + 1) == 0x55
&& p->len >= 3)
{
decode_command_and_feedback(received_data + 2, p->len - 2, 2,
NULL); //0代表UDP
}
else if (*received_data == 0x66 && *(received_data + 1) == 0x66
&& p->len >= 3)
{
GF_BSP_GPIO_SetIO(received_data[3], received_data[2]);
}
else
{
udp_cmd_send_back(received_data, p->len);
}
}
else if (upcb->local_port == UDP_CMD_LOCAL_Android_Listen_PORT)
{
//对PV数据进行修改
//if (*buffer == 0x55 && *(buffer + 1) == 0x55 && length >= 4)
if (received_data[0] != 0x55 || received_data[1] != 0x55 || p->len < 4)
{
return;
}
uint16_t crc_check = ((received_data[p->len - 1] << 8)
| received_data[p->len - 2]);
uint16_t crc_check1 = MB_CRC16(received_data, p->len - 2);
/* CRC 校验正确 */
if (crc_check != MB_CRC16(received_data, p->len - 2)) return;
if (received_data[2] != 0x01 || received_data[3] != 0x01) return;
pb_istream_t i_pv_stream =
{ 0 };
i_pv_stream = pb_istream_from_buffer(&received_data[4], p->len - 4);
pb_decode(&i_pv_stream, PV_struct_define_fields, &decoded_PV);
}
pbuf_free(p);
}
//char UDPprintf[100];
void udp_dlt_send_back(char *pData, uint16_t Size)
{
struct pbuf *p;
/* 分配缓冲区空间 */
p = pbuf_alloc(PBUF_TRANSPORT, Size, PBUF_RAM);
if (p != NULL)
{
/* 填充缓冲区数据 */
pbuf_take(p, pData, Size);
/* 发送udp数据 */
//udp_send(upcb_DLT, p);
err_t t = udp_sendto(upcb_Tx_DLT, p, &serverIP,
UDP_REMOTE_DLT_PORT);
/* 释放缓冲区空间 */
pbuf_free(p);
}
}
void udp_cmd_send_back(char *pData, uint16_t Size)
{
struct pbuf *p;
/* 分配缓冲区空间 */
p = pbuf_alloc(PBUF_TRANSPORT, Size, PBUF_RAM);
if (p != NULL)
{
/* 填充缓冲区数据 */
pbuf_take(p, pData, Size);
/* 发送udp数据 */
err_t err = udp_send(upcb_Tx_Cmd, p);
if (err != ERR_OK)
{
// 发送失败
printf("Failed to send UDP data: %d\n", err);
}
/* 释放缓冲区空间 */
pbuf_free(p);
}
}
void udp_cmd_send_GV(char *pData, uint16_t Size)
{
struct pbuf *p;
/* 分配缓冲区空间 */
p = pbuf_alloc(PBUF_TRANSPORT, Size, PBUF_RAM);
if (p != NULL)
{
/* 填充缓冲区数据 */
pbuf_take(p, pData, Size);
/* 发送udp数据 */
err_t err = udp_send(upcb_Tx_GV, p);
if (err != ERR_OK)
{
// 发送失败
//printf("Failed to send UDP data: %d\n", err);
}
/* 释放缓冲区空间 */
pbuf_free(p);
}
}
void udp_send_by_pcb(struct udp_pcb *upcb, char *pData, uint16_t Size)
{
struct pbuf *p;
/* 分配缓冲区空间 */
p = pbuf_alloc(PBUF_TRANSPORT, Size, PBUF_RAM);
if (p != NULL)
{
/* 填充缓冲区数据 */
pbuf_take(p, pData, Size);
/* 发送udp数据 */
err_t err = udp_send(upcb, p);
if (err != ERR_OK)
{
// 发送失败
//printf("Failed to send UDP data: %d\n", err);
}
/* 释放缓冲区空间 */
pbuf_free(p);
}
}
/******************************************************************************
* : udp客户端
* :
* :
******************************************************************************/
void udp_client_init(void)
{
GF_BSP_Interrupt_Add_CallBack(
DF_BSP_InterCall_TIM8_2ms_PeriodElapsedCallback, UDP_GV_Dispatch);
//将UDP上传IV关闭
GF_BSP_Interrupt_Add_CallBack(
DF_BSP_InterCall_TIM8_2ms_PeriodElapsedCallback, UDP_IV_Dispatch);
//Timer intialize();
err_t err;
IP4_ADDR(&serverIP, 192, 168, 144, 255);
IP4_ADDR(&Android_ServerIP, 192, 168, 144, 20);
/* 创建udp控制块 */
upcb_Rx_DLT = udp_new();
if (upcb_Rx_DLT != NULL)
{
/* 配置本地端口 */
//upcb_DLT->local_port = UDP_DLT_LOCAL_PORT;
/* 配置服务器IP和端口 */
//upcb_DLT->so_options |= SOF_BROADCAST;
//err = udp_connect(upcb_DLT, &serverIP, UDP_REMOTE_DLT_PORT);
err = udp_bind(upcb_Rx_DLT, IP_ADDR_ANY, UDP_DLT_LOCAL_PORT);
if (err == ERR_OK)
{
/* 注册接收回调函数 */
/* 注册接收回调函数 */
udp_recv(upcb_Rx_DLT, udp_receive_callback, NULL);
}
else
{
udp_remove(upcb_Rx_DLT);
}
}
upcb_Rx_From_Android = udp_new();
if (upcb_Rx_From_Android != NULL)
{
/* 配置本地端口 */
//upcb_DLT->local_port = UDP_DLT_LOCAL_PORT;
/* 配置服务器IP和端口 */
//upcb_DLT->so_options |= SOF_BROADCAST;
//err = udp_connect(upcb_DLT, &serverIP, UDP_REMOTE_DLT_PORT);
err = udp_bind(upcb_Rx_From_Android, IP_ADDR_ANY,
UDP_CMD_LOCAL_Android_Listen_PORT);
if (err == ERR_OK)
{
/* 注册接收回调函数 */
/* 注册接收回调函数 */
udp_recv(upcb_Rx_From_Android, udp_receive_callback, NULL);
}
else
{
udp_remove(upcb_Rx_From_Android);
}
}
upcb_Rx_Cmd = udp_new();
if (upcb_Rx_Cmd != NULL)
{
/* 配置本地端口 */
//upcb_Cmd->local_port = UDP_CMD_LOCAL_PORT;
/* 配置服务器IP和端口 */
//upcb_Cmd->so_options |= SOF_BROADCAST;
//err = udp_connect(upcb_Cmd, &serverIP, UDP_REMOTE_CMD_PORT);
err = udp_bind(upcb_Rx_Cmd, IP_ADDR_ANY, UDP_CMD_LOCAL_PORT);
if (err == ERR_OK)
{
/* 注册接收回调函数 */
udp_recv(upcb_Rx_Cmd, udp_receive_callback, NULL);
}
else
{
udp_remove(upcb_Rx_Cmd);
}
}
upcb_Tx_Cmd = udp_new();
if (upcb_Tx_Cmd != NULL)
{
/* 配置本地端口 */
upcb_Tx_Cmd->local_port = UDP_CMD_Send_LOCAL_PORT;
/* 配置服务器IP和端口 */
//upcb_Cmd->so_options |= SOF_BROADCAST;
err = udp_connect(upcb_Tx_Cmd, &serverIP, UDP_REMOTE_CMD_PORT);
if (err == ERR_OK)
{
/* 注册接收回调函数 */
//udp_recv(upcb_Tx_Cmd, udp_receive_callback, NULL);
}
else
{
udp_remove(upcb_Tx_Cmd);
}
}
upcb_Tx_DLT = udp_new();
if (upcb_Tx_DLT != NULL)
{
/* 配置本地端口 */
upcb_Tx_Cmd->local_port = UDP_DLT_Send_LOCAL_PORT;
/* 配置服务器IP和端口 */
//upcb_Cmd->so_options |= SOF_BROADCAST;
err = udp_connect(upcb_Tx_DLT, &serverIP, UDP_REMOTE_DLT_PORT);
if (err == ERR_OK)
{
/* 注册接收回调函数 */
//udp_recv(upcb_Tx_Cmd, udp_receive_callback, NULL);
}
else
{
udp_remove(upcb_Tx_DLT);
}
}
upcb_Tx_GV = udp_new();
if (upcb_Tx_GV != NULL)
{
/* 配置本地端口 */
upcb_Tx_Cmd->local_port = UDP_GV_Send_LOCAL_PORT;
/* 配置服务器IP和端口 */
//upcb_Cmd->so_options |= SOF_BROADCAST;
err = udp_connect(upcb_Tx_GV, &serverIP, UDP_REMOTE_GV_PORT);
if (err == ERR_OK)
{
/* 注册接收回调函数 */
//udp_recv(upcb_Tx_Cmd, udp_receive_callback, NULL);
}
else
{
udp_remove(upcb_Tx_GV);
}
}
upcb_Tx_Android = udp_new();
if (upcb_Tx_Android != NULL)
{
/* 配置本地端口 */
upcb_Tx_Android->local_port = UDP_Android_Send_LOCAL_PORT;
/* 配置服务器IP和端口 */
//upcb_Cmd->so_options |= SOF_BROADCAST;
err = udp_connect(upcb_Tx_Android, &Android_ServerIP,
UDP_REMOTE_Android_PORT);
if (err == ERR_OK)
{
/* 注册接收回调函数 */
//udp_recv(upcb_Tx_Cmd, udp_receive_callback, NULL);
}
else
{
udp_remove(upcb_Tx_Android);
}
}
}
int counter_index = 0;
int iv_counter_index = 0;
void UDP_GV_Dispatch()
{
counter_index++;
if (counter_index <= 50) return;
if (is_udp_GV_update_loop_enalbed == 0) return;
counter_index = 0;
pb_ostream_t GV_o_stream =
{ 0 };
char buf[1024];
GV_o_stream = pb_ostream_from_buffer(&buf[2], sizeof(buf));
pb_encode(&GV_o_stream, GV_struct_define_fields, &GV);
buf[1] = 0xfe;
buf[0] = 0xfe;
//memcpy(&wh_LTE_7S0_Handler->Tx_Buf[2], buf, GV_o_stream.bytes_written);
udp_cmd_send_GV(buf, GV_o_stream.bytes_written + 2);
}
//现在是每一百ms执行一次
void UDP_IV_Dispatch()
{
iv_counter_index++;
if (iv_counter_index <= 50) return;
iv_counter_index=0;
char Tx_Buf[1024];
pb_ostream_t IV_o_stream = pb_ostream_from_buffer(&Tx_Buf[2],
sizeof(Tx_Buf) - 2);
pb_encode(&IV_o_stream, IV_struct_define_fields, &IV);
Tx_Buf[0] = 0x55;
Tx_Buf[1] = 0x55;
int32_t TxCount = IV_o_stream.bytes_written + 4;
uint16_t crc = MB_CRC16(Tx_Buf, IV_o_stream.bytes_written + 2);
Tx_Buf[IV_o_stream.bytes_written + 2] = (crc >> 8) & 0xff;
Tx_Buf[IV_o_stream.bytes_written + 3] = crc & 0xff;
udp_send_by_pcb(upcb_Tx_Android, Tx_Buf, IV_o_stream.bytes_written + 4);
}
/******************************** END OF FILE ********************************/

114
Bingoo/base/bsp_UpperComputer_Handler.c

@ -0,0 +1,114 @@
/*
* bsp_desulfurizer_handler.c
*
* Created on: Jul 29, 2024
* Author: akeguo
*/
#include "msp_WH_LTE_7S0.h"
#include "pb_decode.h"
#include "pb_encode.h"
#include "bsp_include.h"
#include "pb.h"
#include "bsp_Cmd.pb.h"
#include <stdio.h>
#include <stdbool.h>
#include <stdlib.h>
#include "BHBF_ROBOT.h"
#include "bsp_cpu_flash.h"
#include <bsp_qspi_w25q128.h>
#include <bsp_UpperComputer_Handler.h>
#include "bsp_decode_command.h"
void decode_command_from_computer(uint8_t *buffer, uint16_t length);
struct UARTHandler *desulfurizer_message_UART_Handler;
void upper_Computer_UART_Handler_intialize(struct UARTHandler *Handler)
{
//LOG("desulfurizer_message_UART_Handler_intialize");
desulfurizer_message_UART_Handler = Handler;
desulfurizer_message_UART_Handler->dispacherController->Dispacher_Enable=0;//不周期性发送
desulfurizer_message_UART_Handler->Wait_time=30;
desulfurizer_message_UART_Handler->UART_Decode =
decode_command_from_computer; //indicate that there is no need to listen
//desulfurizer_message_UART_Handler->DispacherCallPeriod=200;
//desulfurizer_message_UART_Handler->Add_Dispatcher_List(desulfurizer_message_UART_Handler,steering_set_angle);
}
void send_data_to_upper_computer(double Angle, double WireLength,
double Thickness, char IsFittingPoint,char isMqtt,struct UARTHandler *send_UART_Handler)
{
// LOG("send collected data to computer");
// DesulfurizerMessage _desulfurizer = DesulfurizerMessage_init_default;
// pb_ostream_t output_stream =
// { 0 };
//
// _desulfurizer.Angle = Angle;
// _desulfurizer.WireLength = WireLength;
// _desulfurizer.Thickness = Thickness;
// _desulfurizer.IsFittingPoint = IsFittingPoint;
// char buf[1024];
// output_stream = pb_ostream_from_buffer(buf, sizeof(buf));
// pb_encode(&output_stream, DesulfurizerMessage_fields, &_desulfurizer); //encode to buffer
// Cmd send_Cmd = Cmd_init_default;
//
// //将数据拷贝到Command中
// send_Cmd.CommadNum = 5;
// send_Cmd.Buff_Data_Length = output_stream.bytes_written;
// //拷贝数据到send_Cmd.Buff_Data中
// memcpy(send_Cmd.Buff_Data, buf, send_Cmd.Buff_Data_Length);
// pb_ostream_t Cmd_out_stream =
// { 0 };
//
// if(isMqtt==1)
// {
// Cmd_out_stream = pb_ostream_from_buffer(
// &send_UART_Handler->Tx_Buf[2],
// sizeof(desulfurizer_message_UART_Handler->Tx_Buf)-2);
// pb_encode(&Cmd_out_stream, Cmd_fields, &send_Cmd); //encode to buffer
// send_UART_Handler->Tx_Buf[0]='3';
// send_UART_Handler->Tx_Buf[1]=',';
// send_UART_Handler->TxCount = Cmd_out_stream.bytes_written+2;
// send_UART_Handler->UART_Tx(
// send_UART_Handler);
// }
// else
// {
// Cmd_out_stream = pb_ostream_from_buffer(
// send_UART_Handler->Tx_Buf,
// sizeof(send_UART_Handler->Tx_Buf));
// pb_encode(&Cmd_out_stream, Cmd_fields, &send_Cmd); //encode to buffer
//
// send_UART_Handler->TxCount = Cmd_out_stream.bytes_written;
// send_UART_Handler->UART_Tx(
// send_UART_Handler);
// }
}
void decode_command_from_computer(uint8_t *buffer, uint16_t length)
{
if(*buffer==0x55 && *(buffer+1)==0x55 && length>=3)
{
decode_command_and_feedback(buffer+2, length-2, 0,
desulfurizer_message_UART_Handler);//0代表非mqtt
}
}

126
Bingoo/base/bsp_client_setting.c

@ -0,0 +1,126 @@
/*
* bsp_pv_setting.c
*
* Created on: Jan 8, 2025
* Author: akeguo
*/
#include <bsp_client_setting.h>
#include "BHBF_ROBOT.h"
#include "gpio.h"
#include "BSP/bsp_UART.h"
void UpdateIV();
void decode_received_data_from_client(uint8_t *buffer, uint16_t length);
struct UARTHandler *client_setting_Handler;
DispacherController *client_setting_dispacher;
void client_setting_intialize(struct UARTHandler *Handler)
{
client_setting_Handler = Handler;
client_setting_Handler->Wait_time = 6; // 最低不要低于4;
client_setting_dispacher = Handler->dispacherController;
client_setting_dispacher->Add_Dispatcher_List(client_setting_dispacher,
UpdateIV);
client_setting_dispacher->DispacherCallTime = 500;
client_setting_dispacher->Dispacher_Enable=1;//不周期性发送
LOG("client_setting_intialize");
client_setting_Handler->UART_Decode = decode_received_data_from_client; //indicate that there is no need to listen
}
void UpdateIV()
{
pb_ostream_t IV_o_stream = pb_ostream_from_buffer(
&client_setting_Handler->Tx_Buf[2],
sizeof(client_setting_Handler->Tx_Buf) - 2);
pb_encode(&IV_o_stream, IV_struct_define_fields, &IV);
client_setting_Handler->Tx_Buf[0] = 0x55;
client_setting_Handler->Tx_Buf[1] = 0x55;
client_setting_Handler->TxCount = IV_o_stream.bytes_written + 4;
uint16_t crc=MB_CRC16(&(client_setting_Handler->Tx_Buf[0]), IV_o_stream.bytes_written + 2);
client_setting_Handler->Tx_Buf[IV_o_stream.bytes_written + 2] = (crc>>8) &0xff;
client_setting_Handler->Tx_Buf[IV_o_stream.bytes_written + 3] = crc & 0xff;;
client_setting_Handler->UART_Tx(client_setting_Handler);
}
void decode_received_data_from_client(uint8_t *buffer, uint16_t length)
{
if(length>100)
{
return;
}
uint8_t data[100];
memcpy(data,buffer,length);
//if (*buffer == 0x55 && *(buffer + 1) == 0x55 && length >= 4)
if (buffer[0] == 0x55 && buffer[1] == 0x55 && length >= 4)
{
uint16_t crc_check = ((buffer[length - 1] << 8) | buffer[length - 2]);
uint16_t crc_check1 = MB_CRC16(buffer, length - 2);
/* CRC 校验正确 */
if (crc_check == MB_CRC16(buffer, length - 2))
{
//if (*(buffer + 2) == 0x01 && *(buffer + 3) == 0x01) //01 01 设置PV
if (buffer[2] == 0x01 && buffer[3] == 0x01) //01 01 设置PV
{
pb_istream_t i_pv_stream =
{ 0 };
i_pv_stream = pb_istream_from_buffer(&buffer[4], length - 4);
pb_decode(&i_pv_stream, PV_struct_define_fields, &decoded_PV_variable);
//pb_decode(&i_pv_stream, PV_struct_define_fields, &decoded_PV);
// if(decoded_PV_variable.TimeStamp>decoded_PV.TimeStamp)
// {
// decoded_PV=decoded_PV_variable;
// }
//将CV写入EEPROM
//CV_struct_define saved_cV = GF_BSP_EEPROM_Get_CV();
//GV.PV = decoded_PV;
//GF_BSP_EEPROM_Set_CV(CV);
}
else if (*(buffer + 2) == 0x02 && *(buffer + 3) == 0x01) //设置PV
{
}
else if (*(buffer + 2) == 0x03 && *(buffer + 3) == 0x01) //返回IV
{
}
else
{
}
}
else
{
//Decode Error;
//log_error("wire sensor decoding failed");
LOGFF(DL_ERROR, "android decoding failed");
}
}
// client_setting_Handler->Tx_Buf[0]='1';
// client_setting_Handler->Tx_Buf[1]=',';
// //wh_LTE_7S0_Handler->Tx_Buf[2]='1';
// client_setting_Handler->TxCount = 2;
// client_setting_Handler->UART_Tx(client_setting_Handler);
}

191
Bingoo/base/bsp_com_helper.c

@ -0,0 +1,191 @@
/*
* bsp_com_helper.c
*
* Created on: Oct 9, 2024
* Author: akeguo
*/
#include "bsp_com_helper.h"
#include <stdlib.h>
#include "DLTuc.h"
#include "BHBF_ROBOT.h"
void Dispatch_t(DispacherController *uartHandler)
{
//2ms
if (uartHandler->Dispacher_Enable == 1)
{
if (uartHandler->DispacherNumber > 0) //列表中有数据
{
uartHandler->Dispacher_Counter++;
if (uartHandler->Dispacher_Counter
>= uartHandler->DispacherCallTime / 2
/ (uartHandler->DispacherNumber)) //多长时间运行一次
{
uartHandler->Dispacher_Counter = 0;
if (uartHandler->pHead != NULL
&& uartHandler->pHead->pNext != NULL)
{
uartHandler->pHead->dispache();
uartHandler->pHead = uartHandler->pHead->pNext;
} else
{
}
}
}
}
}
void Dispatcher_List_Add_t(DispacherController *uartHandler,
void (*dispache)(void))
{
Dispatcher *pTmp = NULL; //临时指针2
if (uartHandler->pHead == NULL && uartHandler->pTail == NULL) //头尾部都为空
{
uartHandler->pHead = uartHandler->pTail = (Dispatcher*) malloc(
sizeof(Dispatcher));
uartHandler->pHead->dispache = dispache;
uartHandler->pTail->dispache = dispache;
uartHandler->pHead->pNext = uartHandler->pTail;
uartHandler->pTail->pNext = uartHandler->pHead;
uartHandler->DispacherNumber++;
} else
{
//临时指针2用于逐个申请内存
pTmp = (Dispatcher*) malloc(sizeof(Dispatcher));
pTmp->dispache = dispache;
pTmp->pNext = uartHandler->pHead; //set the new dispatcher .next to the header, thus make it a circle
//临时指针1的next指向刚分配内存的临时指针2
uartHandler->pTail->pNext = pTmp;
uartHandler->pTail = pTmp; //set pTail the last node of this ring
uartHandler->DispacherNumber++;
}
}
void ComHardWare_List_Add_t(HardWareController *uartHandler, char *name,
char value,uint32_t bitFlag)
{
ComHardWare *pTmp = NULL; //临时指针2
if (uartHandler->pComHWHead == NULL && uartHandler->pComHWTail == NULL) //头尾部都为空
{
uartHandler->pComHWHead = uartHandler->pComHWTail =
(ComHardWare*) malloc(sizeof(ComHardWare));
memset(uartHandler->pComHWHead->Name, '\0',
sizeof(uartHandler->pComHWHead->Name));
memcpy(uartHandler->pComHWHead->Name, name, strlen(name));
uartHandler->pComHWHead->IsOnline = value;
uartHandler->pComHWHead->BitFlag = bitFlag;
uartHandler->pComHWHead->pNext = NULL;
} else
{
pTmp = (ComHardWare*) malloc(sizeof(ComHardWare));
memset(pTmp->Name, '\0', sizeof(pTmp->Name));
memcpy(pTmp->Name, name, strlen(name));
pTmp->BitFlag = bitFlag;
pTmp->IsOnline = value;
pTmp->pNext = NULL; //set the new dispatcher .next to the header, thus make it a circle
uartHandler->pComHWTail->pNext = pTmp;
uartHandler->pComHWTail = pTmp;
}
}
//HardWareErrorController->Set_PCOMHardWare = Set_PCOMHardWare_t;
int Set_PCOMHardWare_t(HardWareController *uartHandler, char *name, char value)
{
ComHardWare *ptr = uartHandler->pComHWHead;
char finddata = 0;
if (ptr == NULL)
{
return 0;
}
while (ptr != NULL)
{
if (strcmp(ptr->Name, name) == 0)//相等为0
{
ptr->IsOnline = value;
finddata = 1;
return finddata;
} else
{
ptr = ptr->pNext;
}
}
return finddata;
}
char str1[50] = "\0";
void PCOMHardWare_Check_t(HardWareController *uartHandler)
{
uartHandler->HardWare_Check_Counter++;
// if (uartHandler->HardWare_Check_Counter*2
// >= uartHandler->DispacherCallTime * 6) //make sure every
if (uartHandler->HardWare_Check_Counter * 2 >= uartHandler->DispacherCallTime) //make sure every
{
ComHardWare *ptr = uartHandler->pComHWHead;
if (!ptr)
{
uartHandler->HardWare_Check_Counter = 0;
//printf("链表为空\n");
return;
}
char IsAbnornalStatus = 0;
//check invalid state
while (ptr != NULL)
{
if (ptr->IsOnline != 1) //在线设为1
{
memset(str1, '\0', 50);
memcpy(str1, ptr->Name, strlen(ptr->Name));
LOGFF(DL_ERROR, "connecting Error %s", ptr->Name);
SET_BIT_1(SystemErrorCode,ptr->BitFlag);
//*SystemErrorCode=*SystemErrorCode|(1<<ptr->BitFlag);
IsAbnornalStatus = 1;
}else
{
//*SystemErrorCode=*SystemErrorCode|(1<<ptr->BitFlag);
SET_BIT_0(SystemErrorCode,ptr->BitFlag);
}
ptr = ptr->pNext;
}
//set invalid state
ptr = uartHandler->pComHWHead;
while (ptr != NULL)
{
ptr->IsOnline = 0;
ptr = ptr->pNext;
}
uartHandler->HardWare_Check_Counter = 0;//perform the check of connection
}
}

499
Bingoo/base/bsp_cpu_flash.c

@ -0,0 +1,499 @@
/*
*********************************************************************************************************
*
* : cpu内部falsh操作模块(for STM32H743 H750)
* : bsp_cpu_flash.c
* : V1.1
* : CPU内部Flash的函数
* :
*
* V1.0 2019-09-20 armfly
* V1.1 2019-10-03 armfly flash函数32bug0
* HAL库函数的 HAL_FLASH_Programbug
* PGSERR1 PGSERR2
* Copyright (C), 2019-2030, www.armfly.com
*
*********************************************************************************************************
*/
#include "BSP/bsp_cpu_flash.h"
#include <string.h>
/*
*********************************************************************************************************
*
*********************************************************************************************************
*/
/*
*********************************************************************************************************
*
*********************************************************************************************************
*/
//0x08020000 - 0x08000000 = 128k;//bootload 128k // every sector 448k
/*
*********************************************************************************************************
*
*********************************************************************************************************
*/
__IO uint32_t uwCRCValue;
__IO uint32_t uwExpectedCRCValue;
__IO uint32_t uwAppSize;
uint8_t buf[1024];
uint32_t RecCount = 0;
uint32_t RecCount0 = 0;
uint32_t RecSize = 0;
uint8_t RecCplt = 0;
uint32_t filesize = 0;
uint32_t Bus_Error=0;
uint32_t update_index = 0;
uint32_t update_index_true = 0;
uint32_t update_sum = 0;
uint32_t update_sum_true = 0;
/*
*********************************************************************************************************
* : bsp_GetSector
* :
* :
* : 0-7)
*********************************************************************************************************
*/
uint32_t bsp_GetSector(uint32_t Address)
{
uint32_t sector = 0;
if (((Address < ADDR_FLASH_SECTOR_1_BANK1) && (Address >= ADDR_FLASH_SECTOR_0_BANK1)) || \
((Address < ADDR_FLASH_SECTOR_1_BANK2) && (Address >= ADDR_FLASH_SECTOR_0_BANK2)))
{
sector = FLASH_SECTOR_0;
}
else if (((Address < ADDR_FLASH_SECTOR_2_BANK1) && (Address >= ADDR_FLASH_SECTOR_1_BANK1)) || \
((Address < ADDR_FLASH_SECTOR_2_BANK2) && (Address >= ADDR_FLASH_SECTOR_1_BANK2)))
{
sector = FLASH_SECTOR_1;
}
else if (((Address < ADDR_FLASH_SECTOR_3_BANK1) && (Address >= ADDR_FLASH_SECTOR_2_BANK1)) || \
((Address < ADDR_FLASH_SECTOR_3_BANK2) && (Address >= ADDR_FLASH_SECTOR_2_BANK2)))
{
sector = FLASH_SECTOR_2;
}
else if (((Address < ADDR_FLASH_SECTOR_4_BANK1) && (Address >= ADDR_FLASH_SECTOR_3_BANK1)) || \
((Address < ADDR_FLASH_SECTOR_4_BANK2) && (Address >= ADDR_FLASH_SECTOR_3_BANK2)))
{
sector = FLASH_SECTOR_3;
}
else if (((Address < ADDR_FLASH_SECTOR_5_BANK1) && (Address >= ADDR_FLASH_SECTOR_4_BANK1)) || \
((Address < ADDR_FLASH_SECTOR_5_BANK2) && (Address >= ADDR_FLASH_SECTOR_4_BANK2)))
{
sector = FLASH_SECTOR_4;
}
else if (((Address < ADDR_FLASH_SECTOR_6_BANK1) && (Address >= ADDR_FLASH_SECTOR_5_BANK1)) || \
((Address < ADDR_FLASH_SECTOR_6_BANK2) && (Address >= ADDR_FLASH_SECTOR_5_BANK2)))
{
sector = FLASH_SECTOR_5;
}
else if (((Address < ADDR_FLASH_SECTOR_7_BANK1) && (Address >= ADDR_FLASH_SECTOR_6_BANK1)) || \
((Address < ADDR_FLASH_SECTOR_7_BANK2) && (Address >= ADDR_FLASH_SECTOR_6_BANK2)))
{
sector = FLASH_SECTOR_6;
}
else if (((Address < ADDR_FLASH_SECTOR_0_BANK2) && (Address >= ADDR_FLASH_SECTOR_7_BANK1)) || \
((Address < CPU_FLASH_END_ADDR) && (Address >= ADDR_FLASH_SECTOR_7_BANK2)))
{
sector = FLASH_SECTOR_7;
}
else
{
sector = FLASH_SECTOR_7;
}
return sector;
}
/*
*********************************************************************************************************
* : bsp_ReadCpuFlash
* : CPU Flash的内容
* : _ucpDst :
* _ulFlashAddr :
* _ulSize :
* : 0=1=
*********************************************************************************************************
*/
uint8_t bsp_ReadCpuFlash(uint32_t _ulFlashAddr, uint8_t *_ucpDst, uint32_t _ulSize)
{
uint32_t i;
if (_ulFlashAddr + _ulSize > CPU_FLASH_BASE_ADDR + CPU_FLASH_SIZE)
{
return 1;
}
/* 长度为0时不继续操作,否则起始地址为奇地址会出错 */
if (_ulSize == 0)
{
return 1;
}
for (i = 0; i < _ulSize; i++)
{
*_ucpDst++ = *(uint8_t *)_ulFlashAddr++;
}
return 0;
}
/*
*********************************************************************************************************
* : bsp_CmpCpuFlash
* : Flash指定地址的数据.
* : _ulFlashAddr : Flash地址
* _ucpBuf :
* _ulSize :
* :
* FLASH_IS_EQU 0 Flash内容和待写入的数据相等
* FLASH_REQ_WRITE 1 Flash不需要擦除
* FLASH_REQ_ERASE 2 Flash需要先擦除,
* FLASH_PARAM_ERR 3
*********************************************************************************************************
*/
uint8_t bsp_CmpCpuFlash(uint32_t _ulFlashAddr, uint8_t *_ucpBuf, uint32_t _ulSize)
{
uint32_t i;
uint8_t ucIsEqu; /* 相等标志 */
uint8_t ucByte;
/* 如果偏移地址超过芯片容量,则不改写输出缓冲区 */
if (_ulFlashAddr + _ulSize > CPU_FLASH_BASE_ADDR + CPU_FLASH_SIZE)
{
return FLASH_PARAM_ERR; /* 函数参数错误 */
}
/* 长度为0时返回正确 */
if (_ulSize == 0)
{
return FLASH_IS_EQU; /* Flash内容和待写入的数据相等 */
}
ucIsEqu = 1; /* 先假设所有字节和待写入的数据相等,如果遇到任何一个不相等,则设置为 0 */
for (i = 0; i < _ulSize; i++)
{
ucByte = *(uint8_t *)_ulFlashAddr;
if (ucByte != *_ucpBuf)
{
if (ucByte != 0xFF)
{
return FLASH_REQ_ERASE; /* 需要擦除后再写 */
}
else
{
ucIsEqu = 0; /* 不相等,需要写 */
}
}
_ulFlashAddr++;
_ucpBuf++;
}
if (ucIsEqu == 1)
{
return FLASH_IS_EQU; /* Flash内容和待写入的数据相等,不需要擦除和写操作 */
}
else
{
return FLASH_REQ_WRITE; /* Flash不需要擦除,直接写 */
}
}
/*
*********************************************************************************************************
* : bsp_EraseCpuFlash
* : CPU FLASH一个扇区 128KB)
* : _ulFlashAddr : Flash地址
* : 0 1
* HAL_OK = 0x00,
* HAL_ERROR = 0x01,
* HAL_BUSY = 0x02,
* HAL_TIMEOUT = 0x03
*
*********************************************************************************************************
*/
uint8_t bsp_EraseCpuFlash(uint32_t _ulFlashAddr)
{
uint32_t FirstSector = 0, NbOfSectors = 0;
FLASH_EraseInitTypeDef EraseInitStruct;
uint32_t SECTORError = 0;
uint8_t re;
/* 解锁 */
HAL_FLASH_Unlock();
/* 获取此地址所在的扇区 */
FirstSector = bsp_GetSector(_ulFlashAddr);
/* 固定1个扇区 */
NbOfSectors = 1;
/* 擦除扇区配置 */
EraseInitStruct.TypeErase = FLASH_TYPEERASE_SECTORS;
EraseInitStruct.VoltageRange = FLASH_VOLTAGE_RANGE_3;
if (_ulFlashAddr >= ADDR_FLASH_SECTOR_0_BANK2)
{
EraseInitStruct.Banks = FLASH_BANK_2;
}
else
{
EraseInitStruct.Banks = FLASH_BANK_1;
}
EraseInitStruct.Sector = FirstSector;
EraseInitStruct.NbSectors = NbOfSectors;
/* 扇区擦除 */
re = HAL_FLASHEx_Erase(&EraseInitStruct, &SECTORError);
/* 擦除完毕后,上锁 */
HAL_FLASH_Lock();
return re;
}
/*
*********************************************************************************************************
* : bsp_WriteCpuFlash
* : CPU Flash 32128KB. \
* . 320.
* : _ulFlashAddr : Flash地址
* _ucpSrc :
* _ulSize : , 32
* : 0-1-2-Flash出错(Flash寿命到)
*********************************************************************************************************
*/
uint8_t bsp_WriteCpuFlash(uint32_t _ulFlashAddr, uint8_t *_ucpSrc, uint32_t _ulSize)
{
uint32_t i;
uint8_t ucRet;
/* 如果偏移地址超过芯片容量,则不改写输出缓冲区 */
if (_ulFlashAddr + _ulSize > CPU_FLASH_BASE_ADDR + CPU_FLASH_SIZE)
{
return 1;
}
/* 长度为0时不继续操作 */
if (_ulSize == 0)
{
return 0;
}
ucRet = bsp_CmpCpuFlash(_ulFlashAddr, _ucpSrc, _ulSize);
if (ucRet == FLASH_IS_EQU)
{
return 0;
}
__set_PRIMASK(1); /* 关中断 */
/* FLASH 解锁 */
HAL_FLASH_Unlock();
for (i = 0; i < _ulSize / 32; i++)
{
uint64_t FlashWord[4];
memcpy((char *)FlashWord, _ucpSrc, 32);
_ucpSrc += 32;
if (HAL_FLASH_Program(FLASH_TYPEPROGRAM_FLASHWORD, _ulFlashAddr, (uint64_t)((uint32_t)FlashWord)) == HAL_OK)
{
_ulFlashAddr = _ulFlashAddr + 32; /* 递增,操作下一个256bit */
}
else
{
goto err;
}
}
/* 长度不是32字节整数倍 */
if (_ulSize % 32)
{
uint64_t FlashWord[4];
FlashWord[0] = 0;
FlashWord[1] = 0;
FlashWord[2] = 0;
FlashWord[3] = 0;
memcpy((char *)FlashWord, _ucpSrc, _ulSize % 32);
if (HAL_FLASH_Program(FLASH_TYPEPROGRAM_FLASHWORD, _ulFlashAddr, (uint64_t)((uint32_t)FlashWord)) == HAL_OK)
{
; // _ulFlashAddr = _ulFlashAddr + 32;
}
else
{
goto err;
}
}
/* Flash 加锁,禁止写Flash控制寄存器 */
HAL_FLASH_Lock();
__set_PRIMASK(0); /* 开中断 */
return 0;
err:
/* Flash 加锁,禁止写Flash控制寄存器 */
HAL_FLASH_Lock();
__set_PRIMASK(0); /* 开中断 */
return 1;
}
/*
*********************************************************************************************************
* : JumpToApp
* : JumpToApp
* :
* :
*********************************************************************************************************
*/
void JumpToApp(void)
{
uint32_t i=0;
void (*AppJump)(void); /* 声明一个函数指针 */
/* 关闭全局中断 */
DISABLE_INT();
/* 设置所有时钟到默认状态,使用HSI时钟 */
__HAL_RCC_GPIOH_CLK_DISABLE();
__HAL_RCC_GPIOB_CLK_DISABLE();
HAL_RCC_DeInit();
/* 关闭滴答定时器,复位到默认值 */
SysTick->CTRL = 0;
SysTick->LOAD = 0;
SysTick->VAL = 0;
/* 关闭所有中断,清除所有中断挂起标志 */
for (i = 0; i < 8; i++)
{
NVIC->ICER[i]=0xFFFFFFFF;
NVIC->ICPR[i]=0xFFFFFFFF;
}
/* 使能全局中断 */
ENABLE_INT();
/* 跳转到应用程序,首地址是MSP,地址+4是复位中断服务程序地址 */
AppJump = (void (*)(void)) (*((uint32_t *) (App_Run_Addr + 4)));
/* 设置主堆栈指针 */
__set_MSP(*(uint32_t *)App_Run_Addr);
/* 在RTOS工程,这条语句很重要,设置为特权级模式,使用MSP指针 */
__set_CONTROL(0);
/* 跳转到系统BootLoader */
AppJump();
/* 跳转成功的话,不会执行到这里,用户可以在这里添加代码 */
while (1)
{
}
}
/*
*********************************************************************************************************
* : JumpToApp
* : JumpToApp
* :
* :
*********************************************************************************************************
*/
void Copy_Download_Flash_to_Start()
{
uint32_t startIndex=0;
for(startIndex = 0; startIndex < 3; startIndex++)
{
bsp_EraseCpuFlash((uint32_t)(App_Run_Addr + startIndex*128*1024));//Erase this function
}
uint8_t readData[32];
uint32_t total=3*128*1024/sizeof(readData);
uint8_t retult=0;
for(startIndex=0;startIndex<total;startIndex++)
{
//App_Download_Addr
//Read 32 bytes
bsp_ReadCpuFlash(App_Download_Addr+startIndex*sizeof(readData),readData,sizeof(readData));
//ucState = bsp_WriteCpuFlash((uint32_t)(AppAddr + TotalSize), (uint8_t *)&g_Can2RxData[8], RecSize);
retult=bsp_WriteCpuFlash(App_Run_Addr+startIndex*sizeof(readData),readData,sizeof(readData));
//Read
}
}
void Copy_Peripheral_Download_Flash_to_App_Start(uint32_t totalBytes)
{
uint32_t startIndex=0;
// erase the all the flash from the App_Run_Addr
for(startIndex = 0; startIndex < 7; startIndex++)
{
bsp_EraseCpuFlash((uint32_t)(App_Run_Addr + startIndex*128*1024));//Erase this function
}
uint8_t readData[256];
uint32_t total=totalBytes/sizeof(readData)+1;
uint8_t retult=0;
for(startIndex=0;startIndex<total;startIndex++)
{
//App_Download_Addr
//Read 32 bytes
QSPI_W25Qx_Read_Buffer(&readData,CODE_DOWNLOAD_FLASH_BEGIN_ADDRESS+startIndex*sizeof(readData),256);
HAL_Delay(10);
//retult= bsp_ReadCpuFlash(App_Download_Addr+startIndex*sizeof(readData),readData,sizeof(readData));
//ucState = bsp_WriteCpuFlash((uint32_t)(AppAddr + TotalSize), (uint8_t *)&g_Can2RxData[8], RecSize);
retult=bsp_WriteCpuFlash(App_Run_Addr+startIndex*sizeof(readData),readData,sizeof(readData));
//Read
HAL_Delay(10);
}
}
void Erase_App_Download_Flash_Addr()
{
uint32_t startIndex=0;
//清空bank0 的1-7 区域
//there are 8 sectors in total, and
for(startIndex = 0; startIndex < 4; startIndex++)
{
bsp_EraseCpuFlash((uint32_t)(App_Download_Addr + startIndex*128*1024));//Erase this function
}
//char data[1];
//data[0]=20;
// bsp_WriteCpuFlash(App_Download_Addr,
// data, 1);
}

473
Bingoo/base/bsp_decode_command.c

@ -0,0 +1,473 @@
/*
* bsp_decode_command.c
*
* Created on: Sep 24, 2024
* Author: akeguo
*/
#include "bsp_decode_command.h"
#include "bsp_Error.pb.h"
#include "main.h"
#include "pb.h"
#include "pb_encode.h"
#include "pb_common.h"
#include "fsm_state.h"
#include "motors_power_action.h"
#include "robot_move_actions.h"
#include "fsm_state_control.h"
#define success 1
#define fail 0
Cmd decoded_Cmd = Cmd_init_default;
ReCmd send_Cmd = ReCmd_init_default;
pb_istream_t i_stream =
{ 0 };
char StartDownLoadFlag = 0;
static uint32_t downloadCount = 0;
static uint8_t ReceivedData[1024];
static uint16_t calbriation;
void decode_command_and_feedback(uint8_t *buffer, uint16_t length, char sendWay,
struct UARTHandler *send_Handler)
{
// char array[1000];
// memset(array, 0, sizeof(array));
// memcpy(array, buffer, length);
//
// if (length >= 1)
// {
//
// i_stream = pb_istream_from_buffer(buffer, length);
//
// pb_decode(&i_stream, Cmd_fields, &decoded_Cmd);
//
// memcpy(&decoded_Cmd.Buff_Data,
// &buffer[length - decoded_Cmd.Buff_Data_Length],
// decoded_Cmd.Buff_Data_Length);
//
// switch (decoded_Cmd.CommadNum)
// {
//
// case 17: // 上位机获取控制权
// {
//
// switch (decoded_Cmd.Parameter0)
// {
// case 0:
// {
//
// //read CV
// CV = GF_BSP_EEPROM_Get_CV(); //重新配置CV
// is_upper_computer_take_over_control = 0;
//
// WrapInCmdAndSendMessage(send_Cmd, 10, success,
// "return contorl to Remote Controller success",
// sendWay, send_Handler);
// fsm_state_set(&current_robot_move_state,
// &robot_halt_state);
// //设置电机供电为 On
// //fsm_state_set(&current_motor_power_state, &motor_power_off_state);
// break;
// }
// case 1:
// {
//
// is_upper_computer_take_over_control = 1;
// WrapInCmdAndSendMessage(send_Cmd, 17, success,
// "Take control success", sendWay, send_Handler);
// fsm_state_set(&current_motor_power_state,
// &motor_power_on_state);
// fsm_state_set(&current_robot_move_state,
// &robot_halt_state);
// GV.Robot_Move_Speed = 1000;
// CV.LeftTurnSpeed = 1;
// CV.RightTurnSpeed = 1;
// break;
// }
//
// default:
// break;
//
// }
//
// break;
// }
// case 16: // 上位机手动控制机器人运动
// {
//
// switch (decoded_Cmd.Parameter0)
// {
// case 0:
// {
//
// WrapInCmdAndSendMessage(send_Cmd, 16, success,
// "manual control halt success", sendWay,
// send_Handler);
// fsm_state_set(&current_robot_move_state,
// &robot_halt_state);
// break;
// }
// case 1:
// {
// WrapInCmdAndSendMessage(send_Cmd, 16, success,
// "manual control forward success", sendWay,
// send_Handler);
// fsm_state_set(&current_robot_move_state,
// &robot_forwards_state);
// break;
// }
// case 2:
// {
// WrapInCmdAndSendMessage(send_Cmd, 16, success,
// "manual control backward success", sendWay,
// send_Handler);
// fsm_state_set(&current_robot_move_state,
// &robot_backwards_state);
// break;
// }
// case 3:
// {
// WrapInCmdAndSendMessage(send_Cmd, 16, success,
// "manual control turn left success", sendWay,
// send_Handler);
// fsm_state_set(&current_robot_move_state,
// &robot_turn_left_state);
// break;
// }
// case 4:
// {
// WrapInCmdAndSendMessage(send_Cmd, 16, success,
// "manual control turn right success", sendWay,
// send_Handler);
// fsm_state_set(&current_robot_move_state,
// &robot_turn_right_state);
// break;
// }
// default:
// break;
//
// }
//
// break;
// }
//
// case 15: // 返回错误信息
// {
//
// pb_ostream_t Error_o_stream =
// { 0 };
// char buf[1024];
// Error_o_stream = pb_ostream_from_buffer(buf, sizeof(buf));
// pb_encode(&Error_o_stream, ErrorData_fields,
// &GV.SystemErrorData);
//
// //将数据拷贝到Command中
// send_Cmd.CommadNum = 16;
// send_Cmd.Buff_Data_Length = Error_o_stream.bytes_written;
//
// WrapInCmdAndSend(send_Cmd, buf, sendWay, send_Handler);
//
// break;
// }
//
// case 14: //这里是初始化Flash 好重新写入
// {
// NeedToFeedBackToComputer = 1;
//
// WrapInCmdAndSendMessage(send_Cmd, 14, success,
// "disable periodical call of serialports and can",
// sendWay, send_Handler);
//
// Error_Detect_Enable = 0; //disable ErrorDetect Function;
//
// DLT_LOG_ENABLE_LEVEL = 0; //7 send all information //0 send nothing
//
// //将所有串口的周期性调用暂停
// RS_485_1_UART_Handler.dispacherController->Dispacher_Enable = 0;
// RS_485_2_UART_Handler.dispacherController->Dispacher_Enable = 0;
// RS_485_3_UART_Handler.dispacherController->Dispacher_Enable = 0;
// RS_485_4_UART_Handler.dispacherController->Dispacher_Enable = 0;
// E28_SBUS_UART_Handler.dispacherController->Dispacher_Enable = 0;
// LPUART1_UART_Handler.dispacherController->Dispacher_Enable = 0;
// InterCall_DEBUG_UART_Handler.dispacherController->Dispacher_Enable =
// 0;
// LTE_7S0_Serial_UART_Handler.dispacherController->Dispacher_Enable =
// 0;
// RS_485_4_UART_Handler.dispacherController->Dispacher_Enable = 0;
// is_udp_GV_update_loop_enalbed = 0;
//
// //将CAN总线的周期性调用停掉
// //因为电机有可能处于运动状态,所有CAN线不能停,得发送下去
// //FD_CAN_1_Handler.dispacherController->Dispacher_Enable = 0;
// //FD_CAN_2_Handler.dispacherController->Dispacher_Enable = 0;
// fsm_state_set(&current_robot_move_state, &robot_halt_state);
//
// break;
// }
// case 13: // 使能 GV 周期性性发送数据
// {
// if (decoded_Cmd.Parameter0 == 0) //关闭上传
// {
// NeedToFeedBackToComputer = 1;
// LTE_7S0_Serial_UART_Handler.dispacherController->Dispacher_Enable =
// 0;
// WrapInCmdAndSendMessage(send_Cmd, 14, success,
// "disable send GV", sendWay, send_Handler);
//
// is_udp_GV_update_loop_enalbed = 0;
// }
//
// if (decoded_Cmd.Parameter0 == 1) //打开上传
// {
// NeedToFeedBackToComputer = 0;
// LTE_7S0_Serial_UART_Handler.dispacherController->Dispacher_Enable =
// 1;
// WrapInCmdAndSendMessage(send_Cmd, 14, success,
// "enable send GV", sendWay, send_Handler);
//
// is_udp_GV_update_loop_enalbed = 1;
// }
//
// break;
// }
// case 12: //重启系统,进入bootloader
// {
//
// WrapInCmdAndSendMessage(send_Cmd, 12, success, "STM32 reboot",
// sendWay, send_Handler);
// NVIC_SystemReset();
//
// break;
// }
// case 11: //配置无线网络模块,此处为透传指令
// {
// Send_WH_LTE_7S0_Data(decoded_Cmd.Buff_Data,
// decoded_Cmd.Parameter0);
// break;
// }
// case 10: //擦除flash
// {
// WrapInCmdAndSendMessage(send_Cmd, 10, success,
// "start erasing flash ", sendWay, send_Handler);
// QSPI_W25Qx_EraseDownLoadFlash();
// downloadCount = 0;
// WrapInCmdAndSendMessage(send_Cmd, 10, success,
// "erase flash success", sendWay, send_Handler);
// break;
// }
// case 9: //上位机下发保存软件代码指令
// {
// memcpy(ReceivedData,
// &buffer[length - decoded_Cmd.Buff_Data_Length],
// decoded_Cmd.Buff_Data_Length);
//
// calbriation = MB_CRC16(&ReceivedData,
// decoded_Cmd.Buff_Data_Length);
//
// if (calbriation == decoded_Cmd.Parameter4) //Parameter4是校验
// {
//
// if (downloadCount == decoded_Cmd.Parameter3)
// {
// QSPI_W25Qx_Write_Buffer(&decoded_Cmd.Buff_Data,
// CODE_DOWNLOAD_FLASH_BEGIN_ADDRESS
// + decoded_Cmd.Parameter3,
// decoded_Cmd.Buff_Data_Length);
// downloadCount += decoded_Cmd.Buff_Data_Length;
// send_Cmd.Parameter3 = length;
// WrapInCmdAndSendMessage(send_Cmd, 9, success,
// "download success", sendWay, send_Handler);
//
// }
// else
// {
// decoded_Cmd.Parameter2 = downloadCount; //返回download count;
// send_Cmd.Parameter3 = length;
// WrapInCmdAndSendMessage(send_Cmd, 9, fail,
// "downloadCount!=Parameter3", sendWay,
// send_Handler);
// }
//
// if (decoded_Cmd.Parameter1 == 1)
// {
// WrapInCmdAndSendMessage(send_Cmd, 9, success,
// "download new software sucess", sendWay,
// send_Handler);
// IAP_struct_define iap = GF_BSP_EEPROM_Get_IAP();//Get the version of the code
// iap.UpgradeSucceeded = 1;
// iap.Total_Bytes = decoded_Cmd.Parameter2;
// StartDownLoadFlag = 0;
// downloadCount = 0;
// GF_BSP_EEPROM_Set_IAP(iap);
//
// }
// }
// else
// {
//
// decoded_Cmd.Parameter2 = downloadCount; //返回download count;
// send_Cmd.Parameter3 = length;
// WrapInCmdAndSendMessage(send_Cmd, 9, fail,
// "MB CRC failed and the length ", sendWay,
// send_Handler);
//
// }
//
// break;
// }
//
//// 定义 7 上位机获取拟合点
//// 定义 8 上位机获取位置点 */
// case 8:
// {
//// send_data_to_upper_computer(*Desulfurizer_Angle,
//// *Desulfurizer_Wire_Length, *Desulfurizer_Thickness, 0,
//// 0, desulfurizer_message_UART_Handler);
// break;
// }
// case 7:
// {
//// send_data_to_upper_computer(*Desulfurizer_Angle,
//// *Desulfurizer_Wire_Length, *Desulfurizer_Thickness, 1,
//// 0, desulfurizer_message_UART_Handler);
// break;
// }
// //定义 6 上位机设定编码器角度值为0
// case 6:
// {
// //reset_current_value_0();
// break;
// }
// //定义 4 上位机设定Trace等级值,无返回
// case 4:
// {
//
// break;
// }
// //定义 3 上位机设定CV值
// case 3:
// {
// CV_struct_define decoded_CV = CV_struct_define_init_default;
// pb_istream_t i_cv_stream =
// { 0 };
//
// i_cv_stream = pb_istream_from_buffer(decoded_Cmd.Buff_Data,
// decoded_Cmd.Buff_Data_Length);
// pb_decode(&i_cv_stream, CV_struct_define_fields, &decoded_CV);
// //将CV写入EEPROM
// GF_BSP_EEPROM_Set_CV(decoded_CV);
// CV = decoded_CV;
// send_Cmd.Parameter3 = length;
// WrapInCmdAndSendMessage(send_Cmd, 3, success,
// "Set CV succeeded", sendWay, send_Handler);
// CV_GV_Init();
// break;
// }
// //定义 1 上位机获取默认CV值, 下位机返回CV的值,
// //定义 2 下位机返回CV值
// case 1:
// {
// CV = GF_BSP_EEPROM_Get_CV();
// pb_ostream_t CV_o_stream =
// { 0 };
// char buf[1024];
// CV_o_stream = pb_ostream_from_buffer(buf, sizeof(buf));
// pb_encode(&CV_o_stream, CV_struct_define_fields, &CV);
//
// //将数据拷贝到Command中
// send_Cmd.CommadNum = 2;
// send_Cmd.Buff_Data_Length = CV_o_stream.bytes_written;
//
// WrapInCmdAndSend(send_Cmd, buf, sendWay, send_Handler);
//
// break;
// }
// default:
// WrapInCmdAndSendMessage(send_Cmd, -1, fail,
// "Not the right command", sendWay, send_Handler);
// break;
//
// }
//
// }
// else
// {
//
// }
}
void WrapInCmdAndSend(ReCmd send_Cmd, uint8_t *buf, int8_t sendWay,
struct UARTHandler *send_Handler)
{
memcpy(send_Cmd.Buff_Data, buf, send_Cmd.Buff_Data_Length);
pb_ostream_t ReCmd_out_stream =
{ 0 };
if (sendWay == 1) //MQTT
{
ReCmd_out_stream = pb_ostream_from_buffer(&send_Handler->Tx_Buf[4],
sizeof(send_Handler->Tx_Buf) - 4);
pb_encode(&ReCmd_out_stream, ReCmd_fields, &send_Cmd); //encode to buffer
send_Handler->Tx_Buf[0] = '3';
send_Handler->Tx_Buf[1] = ',';
send_Handler->Tx_Buf[2] = 0xfe;
send_Handler->Tx_Buf[3] = 0xfe;
send_Handler->TxCount = ReCmd_out_stream.bytes_written + 4;
send_Handler->UART_Tx(send_Handler);
}
else if (sendWay == 2) //UDP 发送
{
uint8_t Tx_Buf[2048];
ReCmd_out_stream = pb_ostream_from_buffer(&Tx_Buf[2],
sizeof(Tx_Buf) - 2);
pb_encode(&ReCmd_out_stream, ReCmd_fields, &send_Cmd); //encode to buffer
Tx_Buf[0] = 0xfe;
Tx_Buf[1] = 0xfe;
udp_cmd_send_back(Tx_Buf, ReCmd_out_stream.bytes_written + 2);
}
else //485发送
{
ReCmd_out_stream = pb_ostream_from_buffer(&send_Handler->Tx_Buf[2],
sizeof(send_Handler->Tx_Buf) - 2);
pb_encode(&ReCmd_out_stream, ReCmd_fields, &send_Cmd); //encode to buffer
send_Handler->Tx_Buf[0] = 0xfe;
send_Handler->Tx_Buf[1] = 0xfe;
//send_Handler->AddSendList(send_Handler,send_Handler->Tx_Buf,send_Handler->TxCount,NULL);
send_Handler->TxCount = ReCmd_out_stream.bytes_written + 2;
//send_Handler->TxCount = 200;
send_Handler->UART_Tx(send_Handler);
}
}
//send_Cmd.CommadNum=0xff;//代表返回信息
//send_Cmd.Parameter0 代表执行的指令,发过来的命令号;
//send_Cmd.Parameter1 1 代表成功,0 代表失败;
//send_Cmd.databuf 存的是相关信息,可以通过ACII转成string;
void WrapInCmdAndSendMessage(ReCmd send_Cmd, int8_t functionNum,
int8_t isSuccess, uint8_t *buf, int8_t sendWay,
struct UARTHandler *send_Handler)
{
send_Cmd.CommadNum = 0xff; //代表返回信息
send_Cmd.Parameter0 = functionNum; //代表返回信息
send_Cmd.Parameter1 = isSuccess; //1 代表成功,0 代表失败;
send_Cmd.Buff_Data_Length = strlen(buf);
WrapInCmdAndSend(send_Cmd, buf, sendWay, send_Handler);
}
void send_received_data_to_upper_computer(uint8_t *buffer, uint16_t length)
{
send_Cmd.CommadNum = 12; //定义12为设定Mqtt透传向上返回的数据
send_Cmd.Buff_Data_Length = length;
WrapInCmdAndSend(send_Cmd, buffer, 0, desulfurizer_message_UART_Handler);
}

12
Bingoo/base/bsp_ground_management.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_ground_management.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(ground_management_struct, ground_management_struct, AUTO)

488
Bingoo/base/bsp_qspi_w25q128.c

@ -0,0 +1,488 @@
/*
* bsp_quadspi_W25Q128.c
*
* Created on: Apr 25, 2021
* Author: Administrator
*
*
*
*
*
*/
#include <bsp_qspi_w25q128.h>
#include "quadspi.h"
/* 仅限本文件使用的函数 */
static void QSPI_W25Qx_Write_Enable(QSPI_HandleTypeDef *hqspi);
static uint8_t QSPI_W25Qx_AutoPollingMemRead(uint32_t Timeout);
static void QSPI_W25Qx_Enter(QSPI_HandleTypeDef *hqspi);
static void QSPI_W25Qx_Exit(QSPI_HandleTypeDef *hqspi);
/**
* : Flash状态并等待操作结束
* : Timeout
*
* : Flash的状态
* :
*
*
*/
static uint8_t QSPI_W25Qx_AutoPollingMemRead(uint32_t Timeout)
{
QSPI_CommandTypeDef s_command={0};
QSPI_AutoPollingTypeDef s_config={0};
/* 基本配置 */
s_command.InstructionMode = QSPI_INSTRUCTION_1_LINE; //1线方式发送指令
s_command.AddressSize = QSPI_ADDRESS_24_BITS; //24位地址
s_command.AlternateByteMode = QSPI_ALTERNATE_BYTES_NONE; //无交替字节
s_command.DdrMode = QSPI_DDR_MODE_DISABLE; //W25Q128FV不支持DDR模式
s_command.DdrHoldHalfCycle = QSPI_DDR_HHC_ANALOG_DELAY; //DDR模式,数据输出延迟
s_command.SIOOMode = QSPI_SIOO_INST_EVERY_CMD; //每次传输都发指令
/* 配置自动轮询模式 */
s_command.Instruction = READ_STATUS_REG1_CMD; //读取状态寄存器
s_command.AddressMode = QSPI_ADDRESS_NONE; //没有地址
s_command.DataMode = QSPI_DATA_1_LINE; //1线数据
s_command.DummyCycles = 0; //无空周期
/* 配置自动轮询寄存器(不断查询状态寄存器bit0,等待其为0) */
s_config.Match = 0x00; //等待其为0
s_config.Mask = W25Q128FV_FSR_BUSY; //状态寄存器bit0
s_config.MatchMode = QSPI_MATCH_MODE_AND; //逻辑与
s_config.StatusBytesSize = 1;
s_config.Interval = 0x10;
s_config.AutomaticStop = QSPI_AUTOMATIC_STOP_ENABLE;
/* 自动轮询模式等待编程结束 */
if(HAL_QSPI_AutoPolling(&hqspi,&s_command,&s_config,Timeout) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
return FLASH_OK;
}
/**
* : FLASH的ID
* :
*
* : uint32_t
* :
* 1使SPI模式的指令
*
*/
uint32_t QSPI_W25Qx_ReadID(void)
{
uint32_t uiID;
QSPI_CommandTypeDef s_command = {0};
uint8_t buf[3];
/* 基本配置 */
s_command.InstructionMode = QSPI_INSTRUCTION_1_LINE; //1线方式发送指令
s_command.AddressSize = QSPI_ADDRESS_24_BITS; //24位地址
s_command.AlternateByteMode = QSPI_ALTERNATE_BYTES_NONE; //无交替字节
s_command.DdrMode = QSPI_DDR_MODE_DISABLE; //W25Q128FV不支持DDR模式
s_command.DdrHoldHalfCycle = QSPI_DDR_HHC_ANALOG_DELAY; //DDR模式,数据输出延迟
s_command.SIOOMode = QSPI_SIOO_INST_EVERY_CMD; //每次传输都发指令
/* 读取JEDEC ID */
s_command.Instruction = READ_JEDEC_ID_CMD; //读取ID命令: 0x9F
s_command.AddressMode = QSPI_ADDRESS_NONE; //没有地址
s_command.DataMode = QSPI_DATA_1_LINE; //1线数据
s_command.DummyCycles = 0; //无空周期
s_command.NbData = 3; //读取三个数据
/* 发送指令 */
if(HAL_QSPI_Command(&hqspi,&s_command,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
/* 启动接收 */
if(HAL_QSPI_Receive(&hqspi,buf,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
uiID = (buf[0] << 16) | (buf[1] << 8) | buf[2];
return uiID;
}
/**
* : FLASH写使能
* : hqspi QSPI_HandleTypeDef句柄
*
* :
* :
* 1使SPI模式的指令
*
*/
static void QSPI_W25Qx_Write_Enable(QSPI_HandleTypeDef *hqspi)
{
QSPI_CommandTypeDef s_command = {0};
QSPI_AutoPollingTypeDef s_config={0};
/* 基本配置 */
s_command.InstructionMode = QSPI_INSTRUCTION_1_LINE; //1线方式发送指令
//s_command.AddressSize = QSPI_ADDRESS_24_BITS; //24位地址
s_command.AlternateByteMode = QSPI_ALTERNATE_BYTES_NONE; //无交替字节
s_command.DdrMode = QSPI_DDR_MODE_DISABLE; //W25Q128FV不支持DDR模式
s_command.DdrHoldHalfCycle = QSPI_DDR_HHC_ANALOG_DELAY; //DDR模式,数据输出延迟
s_command.SIOOMode = QSPI_SIOO_INST_EVERY_CMD; //每次传输都发指令
/* 写入使能配置 */
s_command.Instruction = WRITE_ENABLE_CMD; //写使能命令
s_command.AddressMode = QSPI_ADDRESS_NONE; //没有地址
s_command.DataMode = QSPI_DATA_NONE; //没有数据
s_command.DummyCycles = 0; //无空周期
s_command.NbData = 0; //空数据
/* 发送指令 */
if(HAL_QSPI_Command(hqspi,&s_command,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
/* 配置自动轮询模式等待操作完成 */
s_config.Match = W25Q128FV_FSR_WREN;
s_config.Mask = W25Q128FV_FSR_WREN;
s_config.MatchMode = QSPI_MATCH_MODE_AND;
s_config.StatusBytesSize = 1;
s_config.Interval = 0x10;
s_config.AutomaticStop = QSPI_AUTOMATIC_STOP_ENABLE;
s_command.Instruction = READ_STATUS_REG1_CMD;
s_command.DataMode = QSPI_DATA_1_LINE;
s_command.NbData = 1;
if(HAL_QSPI_AutoPolling(hqspi,&s_command,&s_config,HAL_QSPI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
}
/**
* : FLASH的扇区4KB)
* : _uiSectorAddr: 4KB为单位的地址040968192
*
* :
* :
* 1
*
*/
void QSPI_W25Qx_EraseSector(uint32_t _SectorAddr)
{
QSPI_CommandTypeDef s_command = {0};
/* 写使能 */
QSPI_W25Qx_Write_Enable(&hqspi);
/* 基本配置 */
s_command.InstructionMode = QSPI_INSTRUCTION_1_LINE; //1线方式发送指令
s_command.AddressSize = QSPI_ADDRESS_24_BITS; //24位地址
s_command.AlternateByteMode = QSPI_ALTERNATE_BYTES_NONE; //无交替字节
s_command.DdrMode = QSPI_DDR_MODE_DISABLE; //W25Q128FV不支持DDR模式
s_command.DdrHoldHalfCycle = QSPI_DDR_HHC_ANALOG_DELAY; //DDR模式,数据输出延迟
s_command.SIOOMode = QSPI_SIOO_INST_EVERY_CMD; //每次传输都发指令
/* 擦除扇区配置 */
s_command.Instruction = SECTOR_ERASE_CMD; //扇区擦除指令
s_command.AddressMode = QSPI_ADDRESS_1_LINE; //1线地址方式
s_command.DataMode = QSPI_DATA_NONE; //没有数据
s_command.Address = _SectorAddr; //扇区的首地址,保证是4KB整数倍
s_command.DummyCycles = 0; //无空周期
/* 发送指令 */
if(HAL_QSPI_Command(&hqspi,&s_command,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
/* 自动轮询模式等待编程结束 */
if(QSPI_W25Qx_AutoPollingMemRead(W25Q128FV_SUBSECTOR_ERASE_MAX_TIME) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
}
/**
* : QSPI将数据写入外部FALSH
* : _pBuf:
* _write_Addr: 0256512
* _write_Size: 1 ~ 256
* :
* :
* 1W25Q128FV仅仅支持SPI模式写入
*/
uint8_t QSPI_W25Qx_Write_Buffer(uint8_t *_pBuf,uint32_t _write_Addr,uint16_t _write_Size)
{
QSPI_CommandTypeDef s_command = {0};
/* 防止写入的大小超过256字节 */
if(_write_Size > W25Q128FV_PAGE_SIZE)
{
/* 进入断言,提示错误 */
user_Assert(__FILE__,__LINE__);
}
QSPI_W25Qx_Write_Enable(&hqspi); //写使能
/* 基本配置 */
s_command.InstructionMode = QSPI_INSTRUCTION_1_LINE; //1线方式发送指令
s_command.AddressSize = QSPI_ADDRESS_24_BITS; //24位地址
s_command.AlternateByteMode = QSPI_ALTERNATE_BYTES_NONE; //无交替字节
s_command.DdrMode = QSPI_DDR_MODE_DISABLE; //W25Q128FV不支持DDR模式
s_command.DdrHoldHalfCycle = QSPI_DDR_HHC_ANALOG_DELAY; //DDR模式,数据输出延迟
s_command.SIOOMode = QSPI_SIOO_INST_EVERY_CMD; //每次传输都发指令
/*写入序列配置 */
s_command.Instruction = QUAD_INPUT_PAGE_PROG_CMD; //24位四线快速写入指令
s_command.AddressMode = QSPI_ADDRESS_1_LINE; //1线地址方式
s_command.DataMode = QSPI_DATA_4_LINES; //4线数据方式
s_command.Address = _write_Addr; //写入数据的地址
s_command.NbData = _write_Size; //写入数据的大小
s_command.DummyCycles = 0; //无空周期
/* 发送指令 */
if(HAL_QSPI_Command(&hqspi,&s_command,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
/* 启动传输 */
if(HAL_QSPI_Transmit(&hqspi,_pBuf,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
/* 自动轮询模式等待编程结束 */
if(QSPI_W25Qx_AutoPollingMemRead(W25Q128FV_SUBSECTOR_ERASE_MAX_TIME) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
return 1;
}
/**
* : FLASH芯片进入QSPI模式
* : *hqspi: qspi句柄
*
* :
* :
*
*/
static void QSPI_W25Qx_Enter(QSPI_HandleTypeDef *hqspi)
{
QSPI_CommandTypeDef s_command = {0};
/* 配置FLASH进入QPSI模式 */
/* 基本配置 */
s_command.InstructionMode = QSPI_INSTRUCTION_1_LINE; //1线方式发送指令
s_command.AddressSize = QSPI_ADDRESS_24_BITS; //24位地址
s_command.AlternateByteMode = QSPI_ALTERNATE_BYTES_NONE; //无交替字节
s_command.DdrMode = QSPI_DDR_MODE_DISABLE; //W25Q128FV不支持DDR模式
s_command.DdrHoldHalfCycle = QSPI_DDR_HHC_ANALOG_DELAY; //DDR模式,数据输出延迟
s_command.SIOOMode = QSPI_SIOO_INST_EVERY_CMD; //每次传输都发指令
/* 写入序列配置 */
s_command.Instruction = ENTER_QPI_MODE_CMD; //进入QSPI模式
s_command.AddressMode = QSPI_ADDRESS_NONE; //无地址方式
s_command.DataMode = QSPI_DATA_NONE; //无数据方式
s_command.DummyCycles = 0; //0空闲状态周期
/* 发送指令 */
if(HAL_QSPI_Command(hqspi,&s_command,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
}
/**
* : FLASH芯片退出QSPI模式
* : *hqspi: qspi句柄
*
* :
* :
*
*/
static void QSPI_W25Qx_Exit(QSPI_HandleTypeDef *hqspi)
{
QSPI_CommandTypeDef s_command = {0};
/* 基本配置 */
s_command.InstructionMode = QSPI_INSTRUCTION_4_LINES; //4线方式发送指令
s_command.AddressSize = QSPI_ADDRESS_24_BITS; //24位地址
s_command.AlternateByteMode = QSPI_ALTERNATE_BYTES_NONE; //无交替字节
s_command.DdrMode = QSPI_DDR_MODE_DISABLE; //W25Q128FV不支持DDR模式
s_command.DdrHoldHalfCycle = QSPI_DDR_HHC_ANALOG_DELAY; //DDR模式,数据输出延迟
s_command.SIOOMode = QSPI_SIOO_INST_EVERY_CMD; //每次传输都发指令
/* 写入序列配置 */
s_command.Instruction = EXIT_QPI_MODE_CMD; //进入QSPI模式
s_command.AddressMode = QSPI_ADDRESS_NONE; //无地址方式
s_command.DataMode = QSPI_DATA_NONE; //无数据方式
s_command.DummyCycles = 0; //0空闲状态周期
/* 发送指令 */
if(HAL_QSPI_Command(hqspi,&s_command,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
}
/**
* :
* : _pBuf:
* _read_Addr:
* _read_Size: W25Q128FV_PAGE_SIZE,
* :
* :
* 1SPI模式切换到QSPI模式SPI模式SPI模式
*/
void QSPI_W25Qx_Read_Buffer(uint8_t *_pBuf,uint32_t _read_Addr,uint32_t _read_Size)
{
QSPI_CommandTypeDef s_command = {0};
/* 进入QSPI模式 */
QSPI_W25Qx_Enter(&hqspi);
/* 开始从FLASH读取数据 */
/* 基本配置 */
s_command.InstructionMode = QSPI_INSTRUCTION_4_LINES; //1线方式发送指令
s_command.AddressSize = QSPI_ADDRESS_24_BITS; //24位地址
s_command.AlternateByteMode = QSPI_ALTERNATE_BYTES_NONE; //无交替字节
s_command.DdrMode = QSPI_DDR_MODE_DISABLE; //W25Q128FV不支持DDR模式
s_command.DdrHoldHalfCycle = QSPI_DDR_HHC_ANALOG_DELAY; //DDR模式,数据输出延迟
s_command.SIOOMode = QSPI_SIOO_INST_EVERY_CMD; //每次传输都发指令
/*读取序列配置 */
s_command.Instruction = QUAD_INOUT_FAST_READ_CMD; //24位四线快速写入指令
s_command.AddressMode = QSPI_ADDRESS_4_LINES; //4线地址方式
s_command.DataMode = QSPI_DATA_4_LINES; //4线数据方式
s_command.Address = _read_Addr; //写入数据的地址
s_command.NbData = _read_Size; //写入数据的大小
s_command.DummyCycles = 2; //两个空闲状态周期(4个时钟周期),结合时序理解
/* 发送指令 */
if(HAL_QSPI_Command(&hqspi,&s_command,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
/* 读取数据 */
if(HAL_QSPI_Receive(&hqspi,_pBuf,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
/* 退出QSPI模式 */
QSPI_W25Qx_Exit(&hqspi);
}
/**
* : Flash
* :
*
* : void
* :
*
*/
void QSPI_W25Qx_Reset_Memory()
{
QSPI_CommandTypeDef s_command = {0};
/* 基本配置 */
s_command.InstructionMode = QSPI_INSTRUCTION_1_LINE; //1线方式发送指令
s_command.AddressSize = QSPI_ADDRESS_24_BITS; //24位地址
s_command.AlternateByteMode = QSPI_ALTERNATE_BYTES_NONE; //无交替字节
s_command.DdrMode = QSPI_DDR_MODE_DISABLE; //W25Q128FV不支持DDR模式
s_command.DdrHoldHalfCycle = QSPI_DDR_HHC_ANALOG_DELAY; //DDR模式,数据输出延迟
s_command.SIOOMode = QSPI_SIOO_INST_EVERY_CMD; //每次传输都发指令
/* 复位使能W25x */
s_command.Instruction = RESET_ENABLE_CMD; //复位使能命令
s_command.AddressMode = QSPI_ADDRESS_NONE; //没有地址
s_command.DataMode = QSPI_DATA_NONE; //没有数据
s_command.DummyCycles = 0; //无空周期
/* 发送复位使能命令 */
if(HAL_QSPI_Command(&hqspi,&s_command,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
/* 发送复位命令 */
s_command.Instruction = RESET_MEMORY_CMD; //复位命令
/* 发送复位使能命令 */
if(HAL_QSPI_Command(&hqspi,&s_command,HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
/* 自动轮询模式等待等待完成 */
if(QSPI_W25Qx_AutoPollingMemRead(HAL_QPSI_TIMEOUT_DEFAULT_VALUE) != HAL_OK)
{
user_Assert(__FILE__,__LINE__);
}
}
/**
* :
* : file: __FILE__表示源代码文件名
* line: __LINE__表示源代码行号
* void
* :
* 1user_Assert(__FILE__,__LINE__);
*/
void user_Assert(char *file,uint32_t line)
{
printf("Wrong parameters value: file %s on line %d\r\n",file, (unsigned int)line);
/* 这是一个死循环,断言失败时程序会卡此处死机,以便于用户差错 */
if(line == 0)
{
return;
}
while(1)
{
}
}
/**
* : Flash状态并等待操作结束
* : Timeout
*
* : Flash的状态
* :
*
*
*/
void QSPI_W25Qx_EraseDownLoadFlash()
{
int i =0;
int count=CODE_FLASH_STORAGE_SIZE/4/1024;
for(i=0;i<=count;i++)
{
QSPI_W25Qx_EraseSector(i*4*1024);
// HAL_Delay(10);
}
i=10;
}

58
Bingoo/base/bsp_slide_averager.c

@ -0,0 +1,58 @@
/*
* bsp_slide_averager.c
*
* Created on: 2026320
* Author: L1ng the codeGod
*/
#include <stdio.h>
#include <stdint.h>
#include "bsp_slide_averager.h"
// 滑动均值配置(按需修改)
#define WINDOW_SIZE 5 // 窗口长度
/**
* @brief
* @param buffer:
* @param p_index:
* @param p_count:
*/
void slide_averager_init(float buffer[], uint8_t *p_index, uint8_t *p_count) {
// 清空缓冲区
for (uint8_t i = 0; i < WINDOW_SIZE; i++) {
buffer[i] = 0.0f;
}
// 初始化索引和计数
*p_index = 0;
*p_count = 0;
}
/**
* @brief
* @param buffer:
* @param p_index:
* @param p_count:
* @param new_data:
* @retval
*/
float slide_averager_calc(float buffer[], uint8_t *p_index, uint8_t *p_count, float new_data) {
// 1. 存入新数据(覆盖最旧数据)
buffer[*p_index] = new_data;
// 2. 更新索引(循环滑动)
*p_index = (*p_index + 1) % WINDOW_SIZE;
// 3. 更新有效数据计数(窗口未满时累加)
if (*p_count < WINDOW_SIZE) {
(*p_count)++;
}
// 4. 计算均值
float sum = 0.0f;
for (uint8_t i = 0; i < *p_count; i++) {
sum += buffer[i];
}
return sum / *p_count;
}

12
Bingoo/base/bsp_strain_gauge.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "bsp_strain_gauge.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(Strain_Gauge_Struct, Strain_Gauge_Struct, AUTO)

81
Bingoo/base/bsp_tempature.c

@ -0,0 +1,81 @@
/*
* bsp_adc.c
*
* Created on: Feb 21, 2025
* Author: akeguo
*/
#include <bsp_tempature.h>
#include "adc.h"
#include "BSP/bsp_include.h"
#include "stm32h7xx_hal_adc.h"
#include <math.h>
// 硬件相关参数配置
#define ADC_MAX_VALUE 0xffff // 16位ADC最大值,若为10位ADC改为1023
#define VREF 3.3f // ADC参考电压
// 热敏电阻参数 (需根据实际型号确认)
#define R_REF 10000.0f // 分压电阻阻值(与热敏电阻串联)
#define B_VALUE 3380.0f // B常数 (需确认具体型号参数)
#define R0 10000.0f // 25°C时的标称阻值
#define T0 298.15f // 25°C对应的开尔文温度(25 + 273.15)
int32_t adc_value;
void GF_ADC_Collect();
int32_t * tempature;
void ADC_Intialize()
{
GF_BSP_Interrupt_Add_CallBack(
DF_BSP_InterCall_TIM1_100ms_PeriodElapsedCallback, GF_ADC_Collect);
}
void GF_ADC_Collect()
{
*tempature = read_temperature();
}
int32_t read_temperature()
{
HAL_ADC_Start(&hadc2); //开启ADC1
if (HAL_ADC_PollForConversion(&hadc2, 100) == HAL_OK)
{
//16 bit resolution
adc_value = HAL_ADC_GetValue(&hadc2);
HAL_ADC_Stop(&hadc2);
// 1. 计算热敏电阻两端电压
float voltage = (adc_value / (float) ADC_MAX_VALUE) * VREF;
// 2. 计算热敏电阻阻值(分压电路公式)
float ntc_resistance = (voltage * R_REF) / (VREF - voltage);
//float ntc_resistance = (voltage * R_REF) / (VREF);
// 3. 使用Steinhart-Hart方程计算温度
float steinhart;
steinhart = ntc_resistance / R0; // (R/R0)
steinhart = log(steinhart); // ln(R/R0)
steinhart /= B_VALUE; // 1/B * ln(R/R0)
steinhart += 1.0 / T0; // + (1/T0)
steinhart = 1.0 / steinhart; // 取倒数得到开尔文温度
// 4. 转换为摄氏度并返回
return (int32_t)((steinhart - 273.15)*100);
}
else
{
adc_value = 0;
HAL_ADC_Stop(&hadc2);
return 0;
}
}
int32_t temperature;

404
Bingoo/base/change_line_control.c

@ -0,0 +1,404 @@
/*
* change_line_control.c
*
* Created on: 2025812
* Author: xsq
*/
#include "change_line_control.h"
#include "BHBF_ROBOT.h"
#define Veritical_To_Left_Flag 1
#define Veritical_To_Right_Flag 2
int LaneChangeWaittime_ms = 0;
/*
* return: ms
*/
int32_t RunTime_DistanceCm_SpeedE_2MPMin();
int LaneChangeWaittime = 0;
char LaneChangeFlage = -1;
Lane_Vertical_ChangeState Current_Vertical_ChangeState;
LaneChangeControlSTATE VerticalLaneChangeState; /*当前换道处于开始或者结束*/
/* 手动换道
*
// * */
//int LaneChangeControl_Paint()
//{
////机器人SA按键处于中间状态
//// if (P_MK32->CH4_SA == 0)
//// {
//// VerticalLaneChangeState = Lane_Change_Start;
//// Current_Vertical_ChangeState = VerticalChange_StateZero;
////
//// if (abs(GV.Robot_Angle_Desire - CV.RobotUpAngleValue) //头朝上
//// <= 45 * 100)
//// {
//// if (GV.PV.RunMode == Move_Vertical_Move_To_Left)
//// {
//// LaneChangeFlage = Veritical_To_Left_Flag;
////
//// }
//// if (GV.PV.RunMode == Move_Vertical_Move_To_Right)
//// {
//// LaneChangeFlage = Veritical_To_Right_Flag;
////
//// }
//// return 0;
//// }
//// LaneChangeFlage = -1;
//// return 0;
//// }
////
//// if (P_MK32->CH4_SA == -1000) /*竖直上or水平换道*/
//// {
////
//// if (GV.PV.RunMode != Move_Vertical_Move_To_Left
//// && GV.PV.RunMode != Move_Vertical_Move_To_Right)/*竖直换道*/
//// {
//// return 1;
//// }
////
////
//// if (VerticalLaneChangeState != Lane_Change_Start)
//// {
//// fsm_state_set(&current_robot_move_state, &robot_halt_state);
//// return 1;
//// }
////
//// if (LaneChangeFlage == Veritical_To_Left_Flag) /*向左作业*/
//// {
//// Vertical_Lane_Change_From_Right_To_Left_UP_Control(); /*竖直上换道*/
//// return 1;
//// }
//// if (LaneChangeFlage == Veritical_To_Right_Flag) /*向右作业*/
//// {
//// Vertical_Lane_Change_From_Left_To_Right_UP_Control(); /*竖直上换道*/
//// return 1;
//// }
//// return 1;
////
//// }
////
//// if (P_MK32->CH4_SA == 1000) //竖直下换道
//// {
//// if (GV.PV.RunMode != Move_Vertical_Move_To_Left
//// && GV.PV.RunMode != Move_Vertical_Move_To_Right)
//// {
//// return 1;
//// }
////
//// if (VerticalLaneChangeState != Lane_Change_Start) /*换道结束了*/
//// {
//// fsm_state_set(&current_robot_move_state, &robot_halt_state);
//// return 1;
//// }
//// if (LaneChangeFlage == Veritical_To_Left_Flag) /*向左作业*/
//// {
//// Vertical_Lane_Change_From_Right_To_Left_Down_Control(); /*竖直下换道*/
//// return 1;
//// }
//// if (LaneChangeFlage == Veritical_To_Right_Flag) /*向右作业*/
//// {
//// Vertical_Lane_Change_From_Left_To_Right_Down_Control(); /*竖直下换道*/
//// return 1;
//// }
//// return 1;
//// }
////
//// return 0;
//
//}
//
//
//
///* 竖直从左往右作业 上端 向右换道 最终头朝上
// * */
//void Vertical_Lane_Change_From_Left_To_Right_UP_Control()
//{
//
// GV.Robot_Move_Speed = speed_M_min_toE01_M_min( CV.Lane_Change_Speed_m_per_min);
// switch (Current_Vertical_ChangeState)
// {
// case VerticalChange_StateZero:
// {
// Current_Vertical_ChangeState = VerticalChange_TurnToLeft;
// break;
// }
// case VerticalChange_TurnToLeft:
// {
// if (abs(GV.Robot_Angle_Desire - CV.RobotLeftAngleValue)
// >= CV.Allowable_Error_For_Angle_Tracking)
// {
// fsm_state_set(&current_robot_move_state,
// &robot_move_head_to_left_enum_state); /* 移动至头朝左 */
// }
// else
// {
//
// fsm_state_set(&current_robot_move_state,
// &robot_move_horizontal_task_backwards_left_state);/* 水平纠偏后退 头朝左*/
// //开启计时
// timer_handler_1.start_timer = 1;
// Current_Vertical_ChangeState = VerticalChange_DelayMove;
// }
// break;
// }
// case VerticalChange_DelayMove:
// {
// LaneChangeWaittime = RunTime_DistanceCm_SpeedE_2MPMin();
// if (CompareTimer(LaneChangeWaittime, &timer_handler_1))
// {
//
// Current_Vertical_ChangeState = VerticalChange_TurnToUP;
// }
// break;
// }
// case VerticalChange_TurnToUP:
// {
// if (abs(GV.Robot_Angle_Desire - CV.RobotUpAngleValue)
// >= CV.Allowable_Error_For_Angle_Tracking)
// {
// fsm_state_set(&current_robot_move_state,
// &robot_move_head_to_up_enum_state); /* 移动至头朝上 */
// }
// else
// {
// Current_Vertical_ChangeState = VerticalChange_End;
// }
//
// break;
// }
// case VerticalChange_End:
// {
// VerticalLaneChangeState = Lane_Change_Stop;
// break;
// }
// default:
// break;
// }
//}
//
///* 竖直从左往右作业 下端 向右换道 最终头朝上
// * */
//void Vertical_Lane_Change_From_Left_To_Right_Down_Control()
//{
//
// GV.Robot_Move_Speed = speed_M_min_toE01_M_min( CV.Lane_Change_Speed_m_per_min);
// switch (Current_Vertical_ChangeState)
// {
// case VerticalChange_StateZero:
// {
// Current_Vertical_ChangeState = VerticalChange_TurnToRight;
//
// break;
// }
// case VerticalChange_TurnToRight:
// {
// if (abs(GV.Robot_Angle_Desire - CV.RobotRightAngleValue)
// >= CV.Allowable_Error_For_Angle_Tracking)
// {
// fsm_state_set(&current_robot_move_state,
// &robot_move_head_to_right_enum_state); /* 移动至头朝右 */
// }
// else
// {
//
// fsm_state_set(&current_robot_move_state,
// &robot_move_horizontal_task_forwards_right_state);/* 水平纠偏前进 头朝右*/
// //开启计时
// timer_handler_1.start_timer = 1;
// Current_Vertical_ChangeState = VerticalChange_DelayMove;
// }
// break;
// }
// case VerticalChange_DelayMove:
// {
// LaneChangeWaittime = RunTime_DistanceCm_SpeedE_2MPMin();
// if (CompareTimer(LaneChangeWaittime, &timer_handler_1))
// {
//
// Current_Vertical_ChangeState = VerticalChange_TurnToUP;
//
// }
// break;
// }
// case VerticalChange_TurnToUP:
// {
// if (abs(GV.Robot_Angle_Desire - CV.RobotUpAngleValue)
// >= CV.Allowable_Error_For_Angle_Tracking) //误差在1度内
// {
// fsm_state_set(&current_robot_move_state,
// &robot_move_head_to_up_enum_state); /* 移动至头朝上 */
// }
// else
// {
// Current_Vertical_ChangeState = VerticalChange_End;
// }
// break;
// }
// case VerticalChange_End:
// {
// VerticalLaneChangeState = Lane_Change_Stop;
// break;
// }
// default:
// break;
// }
//
//}
//
//
///* 竖直从右往左作业 上端 向左换道 最终头朝上
// * */
//void Vertical_Lane_Change_From_Right_To_Left_UP_Control()
//{
//
// GV.Robot_Move_Speed = speed_M_min_toE01_M_min( CV.Lane_Change_Speed_m_per_min);
// switch (Current_Vertical_ChangeState)
// {
// case VerticalChange_StateZero:
// {
// Current_Vertical_ChangeState = VerticalChange_TurnToRight;
// break;
// }
// case VerticalChange_TurnToRight:
// {
// if (abs(GV.Robot_Angle_Desire - CV.RobotRightAngleValue)
// >= CV.Allowable_Error_For_Angle_Tracking)
// {
// fsm_state_set(&current_robot_move_state,
// &robot_move_head_to_right_enum_state); /* 移动至头朝右 */
// }
// else
// {
//
// fsm_state_set(&current_robot_move_state,
// &robot_move_horizontal_task_backwards_right_state);/* 水平纠偏后退 头朝右*/
// //开启计时
// timer_handler_1.start_timer = 1;
// Current_Vertical_ChangeState = VerticalChange_DelayMove;
// }
// break;
// }
// case VerticalChange_DelayMove:
// {
// LaneChangeWaittime = RunTime_DistanceCm_SpeedE_2MPMin();
// if (CompareTimer(LaneChangeWaittime, &timer_handler_1))
// {
// Current_Vertical_ChangeState = VerticalChange_TurnToUP;
// }
// break;
// }
// case VerticalChange_TurnToUP:
// {
// if (abs(GV.Robot_Angle_Desire - CV.RobotUpAngleValue)
// >= CV.Allowable_Error_For_Angle_Tracking)
// {
// fsm_state_set(&current_robot_move_state,
// &robot_move_head_to_up_enum_state); /* 移动至头朝上 */
// }
// else
// {
// Current_Vertical_ChangeState = VerticalChange_End;
// }
//
// break;
// }
// case VerticalChange_End:
// {
// VerticalLaneChangeState = Lane_Change_Stop;
// break;
// }
// default:
// break;
// }
//
//}
//
///* 竖直从右往左作业 下端 向左换道 最终头朝上
// * */
//void Vertical_Lane_Change_From_Right_To_Left_Down_Control()
//{
//
// GV.Robot_Move_Speed = speed_M_min_toE01_M_min( CV.Lane_Change_Speed_m_per_min);//转完 前进or后退得速度
// switch (Current_Vertical_ChangeState)
// {
// case VerticalChange_StateZero:
// {
// Current_Vertical_ChangeState = VerticalChange_TurnToLeft;
//
// break;
// }
// case VerticalChange_TurnToLeft:
// {
// if (abs(GV.Robot_Angle_Desire - CV.RobotLeftAngleValue)
// >= CV.Allowable_Error_For_Angle_Tracking)
// {
// fsm_state_set(&current_robot_move_state,
// &robot_move_head_to_left_enum_state); /* 移动至头朝左 */
// }
// else
// {
// fsm_state_set(&current_robot_move_state,
// &robot_move_horizontal_task_forwards_left_state);/* 水平纠偏前进 头朝左*/
// //开启计时
// timer_handler_1.start_timer = 1;
// Current_Vertical_ChangeState = VerticalChange_DelayMove;
// }
// break;
// }
// case VerticalChange_DelayMove:
// {
// LaneChangeWaittime = RunTime_DistanceCm_SpeedE_2MPMin();
// if (CompareTimer(LaneChangeWaittime, &timer_handler_1))
// {
//
// Current_Vertical_ChangeState = VerticalChange_TurnToUP;
//
// }
// break;
// }
// case VerticalChange_TurnToUP:
// {
// if (abs(GV.Robot_Angle_Desire - CV.RobotUpAngleValue)
// >= CV.Allowable_Error_For_Angle_Tracking) //误差在1度内
// {
// fsm_state_set(&current_robot_move_state,
// &robot_move_head_to_up_enum_state); /* 移动至头朝上 */
// }
// else
// {
// Current_Vertical_ChangeState = VerticalChange_End;
// }
// break;
// }
// case VerticalChange_End:
// {
// VerticalLaneChangeState = Lane_Change_Stop;
// break;
// }
// default:
// break;
// }
//
//}
//
///*
// * return: ms
// */
//int32_t RunTime_DistanceCm_SpeedE_2MPMin()
//{
//
//// LaneChangeWaittime_ms = 600 * (GV.PV.LaneChangeDistance+CV.Vertical_ChangeLane_Compensation)
//// / CV.Lane_Change_Speed_m_per_min;
////
//// return LaneChangeWaittime_ms;
//
//}

51
Bingoo/base/fsm_state.c

@ -0,0 +1,51 @@
/*
* fsm.c
*
* Created on: 2025714
* Author: akeguo
*/
#include "fsm_state.h"
#include "stdint.h"
void fsm_state_run(transition_t* p_this)
{
// turnstile_pass(&turnstile)
if (p_this->p_state->robotRun!= NULL)
{
p_this->p_state->robotRun(p_this);
}
}
//修改状态机状态,若状态机修改后,则查看是否有enter 和 exit命令进行运动
void fsm_state_set(transition_t* p_this, transition_state_t* p_new_state)
{
if(p_this==NULL){return;}
// turnstile_pass(&turnstile)
if (p_this->p_state!= p_new_state) /* 状态不等 */
{
if (p_this->p_state->robotExit!=NULL)
{
p_this->p_state->robotExit(p_this);
}
p_this->p_state = p_new_state;
if (p_this->p_state->robotEnter != NULL)
{
p_this->p_state->robotEnter(p_this);
}
//exit
}
}
//状态机初始化设定
void fsm_state_init(transition_t* p_this,transition_state_t* inti_state)
{
p_this->p_state =inti_state;
}

414
Bingoo/base/fsm_state_control.c

@ -0,0 +1,414 @@
/*
* fsm_state_control.c
*
* Created on: Jan 13, 2026
* Author: bm673
*/
/*=========================== 1. 头文件包含 ===========================*/
#include "fsm_state_control.h"
#include "Handset_Status_Setting.h"
#include "robot_move_actions.h"
#include "paint_gun_action.h"
#include "swing_action.h"
#include "motors_power_action.h"
#include "BHBF_ROBOT.h"
/*=========================== 2. 宏定义 ===========================*/
/* 本文件无宏定义,预留 */
/*=========================== 3. 类型定义 ===========================*/
/* 本文件无自定义类型,预留 */
/*=========================== 4. 全局变量 ===========================*/
/* 调试变量(普通全局变量) */
Robot_Mode g_debug_prev_mode = Halt_Mode;
InputEvent g_debug_curr_key = INPUT_NONE;
ActionFunc g_debug_current_action_func = NULL;
int error_detcet=0; //获取机器人错误
uint32_t NVIC_Priority_Group; // 中断优先级分组
uint32_t TIM8_PreemptPrio; // 定时器8 抢占优先级
uint32_t TIM8_SubPrio; // 定时器8 子优先级
/*=========================== 5. 静态函数声明 ===========================*/
/* 组函数(仅本文件使用) */
static void manual_forward_group(void);
static void manual_backward_group(void);
static void manual_left_group(void);
static void manual_right_group(void);
static void manual_auto_group(void);
static void horizontal_forward_group(void);
static void horizontal_backward_group(void);
static void weld_auto_group(void);
static void change_Road_group(void);
static void vertical_forward_group(void); /* 虽未在表中使用,但保留 */
static void vertical_backward_group(void);
static void horizontal_auto_group(void);
static void vertical_auto_group(void);
static void Emergency_Stop_group(void);
// 读取指定中断的抢占/子优先级,存入全局变量
void Read_IRQ_Priority(IRQn_Type IRQn, uint32_t *preempt, uint32_t *sub);
/*=========================== 6. 函数指针表 ===========================*/
/* 动作映射表:模式 × 按键 -> 执行函数 */
ActionFunc actionTable[MODE_COUNT][KEY_COUNT] = {
// Halt_Mode - 所有输入都无操作
[Halt_Mode] = { [0 ... KEY_COUNT-1] = Robot_Stop },
// Manual_Mode - 手动模式
[Manual_Mode] = {
[INPUT_ROCKER_STOP] = Robot_Stop,
[INPUT_ROCKER_FORWARD] = manual_forward_group,
[INPUT_ROCKER_BACKWARD] = manual_backward_group,
[INPUT_ROCKER_TURN_LEFT] = manual_left_group,
[INPUT_ROCKER_TURN_RIGHT] = manual_right_group,
[INPUT_KEY_FORWARD_CRUISE] = manual_forward_group,
[INPUT_KEY_BACKWARD_CRUISE] = manual_backward_group,
[INPUT_KEY_AUTO_WORK_UP] = manual_auto_group,
[INPUT_KEY_LANE_CHANGE_UP] = Robot_Stop,
[EMERGENCE_STOP] = Emergency_Stop_group,
},
// Horizontal_Mode - 水平模式
[Horizontal_Mode] = {
[INPUT_ROCKER_STOP] = Robot_Stop,
[INPUT_ROCKER_FORWARD] = horizontal_forward_group,
[INPUT_ROCKER_BACKWARD] = horizontal_backward_group,
[INPUT_ROCKER_TURN_LEFT] = manual_left_group,
[INPUT_ROCKER_TURN_RIGHT] = manual_right_group, //等待调整 INPUT_KEY_FORWARD_CRUISE
[INPUT_KEY_FORWARD_CRUISE] = horizontal_forward_group,
[INPUT_KEY_BACKWARD_CRUISE] = horizontal_backward_group,
[INPUT_KEY_AUTO_WORK_UP] = horizontal_auto_group,
[INPUT_KEY_LANE_CHANGE_UP] = change_Road_group,
[EMERGENCE_STOP] = Emergency_Stop_group,
// 其他按键暂未实现,留空(NULL)
},
// Flat_Mode - 暂时用于焊缝模式(预留)
[Flat_Mode] = {
[INPUT_ROCKER_STOP] = Robot_Stop,
[INPUT_ROCKER_FORWARD] = manual_forward_group,
[INPUT_ROCKER_BACKWARD] = manual_backward_group,
[INPUT_ROCKER_TURN_LEFT] = manual_left_group,
[INPUT_ROCKER_TURN_RIGHT] = manual_right_group,
[INPUT_KEY_AUTO_WORK_UP] = weld_auto_group,
[EMERGENCE_STOP] = Emergency_Stop_group,
// 暂时用于焊缝跟踪
},
// Vertical_Mode_Left - 左侧垂直模式
[Vertical_Mode_Left] = {
[INPUT_ROCKER_STOP] = Robot_Stop,
[INPUT_ROCKER_FORWARD] = vertical_forward_group, // 注意:水平前进,可能是复用
[INPUT_ROCKER_BACKWARD] = vertical_backward_group,
[INPUT_ROCKER_TURN_LEFT] = manual_left_group,
[INPUT_ROCKER_TURN_RIGHT] = manual_right_group, //等待调整
[INPUT_KEY_FORWARD_CRUISE] = vertical_forward_group,
[INPUT_KEY_BACKWARD_CRUISE] = vertical_backward_group,
[INPUT_KEY_LANE_CHANGE_UP] = change_Road_group,
[INPUT_KEY_AUTO_WORK_UP] = vertical_auto_group,
[EMERGENCE_STOP] = Emergency_Stop_group,
// 其他预留
},
// Vertical_Mode_Right - 右侧垂直模式(预留)
[Vertical_Mode_Right] = {
[INPUT_ROCKER_STOP] = Robot_Stop,
[INPUT_ROCKER_FORWARD] = vertical_forward_group, // 注意:水平前进,可能是复用
[INPUT_ROCKER_BACKWARD] = vertical_backward_group,
[INPUT_ROCKER_TURN_LEFT] = manual_left_group,
[INPUT_ROCKER_TURN_RIGHT] = manual_right_group, //等待调整
[INPUT_KEY_FORWARD_CRUISE] = vertical_forward_group,
[INPUT_KEY_BACKWARD_CRUISE] = vertical_backward_group,
[INPUT_KEY_LANE_CHANGE_UP] = change_Road_group,
[INPUT_KEY_AUTO_WORK_UP] = vertical_auto_group,
[EMERGENCE_STOP] = Emergency_Stop_group,
// 未实现
},
// Regional_Horizontal_Automatic_Task - 区域水平自动任务
[Regional_Horizontal_Automatic_Task] = {
// 未实现
},
// Regional_Flat_Automatic_Task - 区域平面自动任务
[Regional_Flat_Automatic_Task] = {
// 未实现
}
};
/*=========================== 7. 静态函数实现 ===========================*/
/*-------------------------------------------------------------------
*
*-------------------------------------------------------------------*/
static void manual_forward_group(void)
{
Manually_Forward();
PaintGun_Contronl();
Robot_Swing_Operation_Function();
}
static void manual_backward_group(void)
{
Manually_Backward();
PaintGun_Contronl();
Robot_Swing_Operation_Function();
}
static void manual_left_group(void)
{
Turn_Left();
PaintGun_Contronl();
Robot_Swing_Operation_Function();
}
static void manual_right_group(void)
{
Turn_Right();
PaintGun_Contronl();
Robot_Swing_Operation_Function();
}
static void horizontal_forward_group(void)
{
GV.Robot_Desired_Speed=GV.Robot_Move_Speed;
horizontal_forward();
PaintGun_Contronl_Press();
Robot_Swing_Operation_Function();
/* 若需喷枪控制,可在此添加 */
}
static void horizontal_backward_group(void)
{
GV.Robot_Desired_Speed=-GV.Robot_Move_Speed;
horizontal_forward();
PaintGun_Contronl_Press();
Robot_Swing_Operation_Function();
/* 若需喷枪控制,可在此添加 */
}
static void manual_auto_group(void)
{
Move_Manual_Auto_Sub_Func();
PaintGun_Contronl_Press();
}
static void horizontal_auto_group(void)
{
// horizontal_work();
Move_Horizontal_Auto_Sub_Func();
PaintGun_Contronl_Press();
/* 若需喷枪控制,可在此添加 */
}
static void weld_auto_group(void)
{
GV.Robot_Desired_Speed=-GV.Robot_Move_Speed;
Weld_Auto_Sub_Func();
PaintGun_Contronl_Press();
/* 若需喷枪控制,可在此添加 */
}
static void change_Road_group(void)
{
Change_Road_Func();
PaintGun_Contronl_Press();
/* 若需喷枪控制,可在此添加 */
}
static void vertical_forward_group(void)
{
GV.Robot_Desired_Speed=GV.Robot_Move_Speed;
vertical_forward();
PaintGun_Contronl_Press();
Robot_Swing_Operation_Function();
}
static void vertical_backward_group(void)
{
GV.Robot_Desired_Speed=-GV.Robot_Move_Speed;
vertical_forward();
PaintGun_Contronl_Press();
Robot_Swing_Operation_Function();
}
static void vertical_auto_group(void)
{
// horizontal_work();
Move_Vertical_Auto_Sub_Func();
PaintGun_Contronl_Press();
/* 若需喷枪控制,可在此添加 */
}
static void Emergency_Stop_group(void)
{
Emergency_Stop_Action();
Is_All_Button_Reset = 0;
}
/*=========================== 8. 对外接口函数(需外部调用) ===========================*/
int AbnormalDetect(void);
/*-------------------------------------------------------------------
*
*-------------------------------------------------------------------*/
void Fsm_Init(void)
{
// 原注释掉的初始化代码
// current_robot_move_state.p_state = &robot_halt_state;
// current_paintgun_state.p_state = &paintgun_off_state;
// current_motor_power_state.p_state = &motor_power_off_state;
GV.GroundManagementValue.MaualControlPower=0;
GF_BSP_Interrupt_Add_CallBack(DF_BSP_InterCall_TIM8_2ms_PeriodElapsedCallback, GF_Dispatch);
}
/*-------------------------------------------------------------------
* 2ms
*-------------------------------------------------------------------*/
Robot_Mode g_debug_pre_mode = Halt_Mode;
int robot_start_flag=0;
int watch_dog=0;
void GF_Dispatch(void)
{
Read_IRQ_Priority(TIM8_UP_TIM13_IRQn, &TIM8_PreemptPrio, &TIM8_SubPrio);
static int32_t start_time=0; //机器人上电启动时间约30s
if(start_time<20000)
{
start_time++;
//SystemErrorCode = 0;
}
else
{
error_detcet=AbnormalDetect();
IV.robot_start=2; //表示机器人成功启动
}
IV_control();
static Robot_Mode prev_mode = Halt_Mode;
static InputEvent prev_key = INPUT_ROCKER_STOP;
static ActionFunc prev_action_func = NULL;
g_debug_pre_mode=prev_mode;
// 获取当前模式和按键
InputEvent curr_key = RemoteControl_GetKeyIndex(prev_mode);
// 仅按键变化时更新动作
if (curr_key != prev_key)
{
robot_start_flag=1;
PV_control();
prev_mode = RobotRockerState();
prev_key = curr_key;
//若有错误只保留手动模式
if(error_detcet)
{
prev_mode=Manual_Mode;
}
prev_action_func = actionTable[prev_mode][prev_key];
}
// 执行动作
if (prev_action_func != NULL)
{
prev_action_func();
g_debug_current_action_func = prev_action_func;
}
if(robot_start_flag==0) //保证上电之后摆臂就能动,不加这句的话,就要先动其它摇杆,摆臂才能动
{
Robot_Swing_Operation_Function();
}
flag_reset();
// 更新调试变量
g_debug_prev_mode = prev_mode;
g_debug_curr_key = curr_key;
Compensation_Update();
get_weld_data();
}
/*-------------------------------------------------------------------
*
*-------------------------------------------------------------------*/
int cnt=0;
int AbnormalDetect(void)
{
/* SBUS 出错 */
if (Get_BIT(SystemErrorCode, ComError_Mk32_SBus) == DISCONNECTED
||(Get_BIT(SystemErrorCode, ComError_ZQ_CAN_ID1_LeftMotor) == DISCONNECTED)
||(Get_BIT(SystemErrorCode, ComError_ZQ_CAN_ID2_RightMotor) == DISCONNECTED)
||(Get_BIT(SystemErrorCode, ComError_ZQ_CAN_ID3_SwingMotor) == DISCONNECTED)
||(Get_BIT(SystemErrorCode, ComError_Ground_Management) == DISCONNECTED))
{
cnt++;
if(cnt>250)
{
//触发软急停
GV.GroundManagementValue.MaualControlPower=1;
GV.GroundManagementValue.MaualPowerState=0;
cnt=0;
return 1;
}
}
/* 串口出错 */
if (Get_BIT(SystemErrorCode, ComError_MK32_Serial) == DISCONNECTED)
{
return 2;
}
/* 陀螺仪无信号 */
if (Get_BIT(SystemErrorCode, ComError_TL720D) == DISCONNECTED)
{
return 4;
}
/* 遥控器关机或失联 */
if (P_MK32->IsOnline == 0)
{
GV.GroundManagementValue.MaualControlPower=1;
GV.GroundManagementValue.MaualPowerState=0;
Is_All_Button_Reset = 0;
return 6;
}
/* 按钮未复位 */
if (Get_BIT(SystemErrorCode, ComError_MK32_InitialState) != Has_Reset)
{
return 3;
}
return 0;
}
// 读取指定中断的抢占/子优先级,存入全局变量
void Read_IRQ_Priority(IRQn_Type IRQn, uint32_t *preempt, uint32_t *sub)
{
// 调用你官方的4参数HAL函数
HAL_NVIC_GetPriority(IRQn, NVIC_Priority_Group, preempt, sub);
}

279
Bingoo/base/motor.c

@ -0,0 +1,279 @@
/*
* motor.c
*
* Created on: 2026129
* Author: bm673
*/
#include "motors.h"
#include "msp_TTMotor_ZQ.h"
FDCANHandler *Roughening_Motor_Controller;
FDCANHandler *Roughening_Motor_Controller_CAN2;
DispacherController *Roughening_DispacherController;
DispacherController *Roughening_DispacherController_CAN2;
char TT_Motor_Need_To_Activate = 1;
char TT_Motor_Need_To_Activate_1 = 1;
float Move_Base_Speed_Count_m_Min=201.7*7.64;//天太电机1m/min
float Swing_Speed_Deg_Sencond_motor=201.7;//HJ32-121
int middle_position_motor=-944334;
#define TT_One_Deg_Count_motor 11014///32768*121/360(减速比121)=11014
//MotorParameters *TT_Motor[7];
void MotorCommandsLoop();
void MotorCommandsLoop_2();
void MotorCommandsLoop_2_Position();
void Roughening_MotorDecodeCAN(uint32_t canID, uint8_t *buffer, uint32_t length);
void Roughening_MotorDecodeCAN2(uint32_t canID, uint8_t *buffer, uint32_t length);
extern int32_t start_time;
void Motor_Controller_intialize(FDCANHandler *Handler)
{
//初始化
Roughening_Motor_Controller = Handler;
Roughening_Motor_Controller->CAN_Decode = Roughening_MotorDecodeCAN;
HardWareErrorController->Add_PCOMHardWare(HardWareErrorController,"ZQ_CAN_ID1_LeftMotor", 1, ComError_ZQ_CAN_ID1_LeftMotor);
HardWareErrorController->Add_PCOMHardWare(HardWareErrorController,"ZQ_CAN_ID2_RightMotor", 1, ComError_ZQ_CAN_ID2_RightMotor);
Roughening_DispacherController = Handler->dispacherController;
Roughening_DispacherController->DispacherCallTime = 2;
Roughening_DispacherController->Add_Dispatcher_List(Roughening_DispacherController, MotorCommandsLoop);
//电机绑定
TT_Motor[1]=&GV.LeftMotor;
TT_Motor[2]=&GV.RightMotor;
TT_Motor[1]->MotorID=1;
TT_Motor[2]->MotorID=2;
}
void Motor_Controller_intialize_CAN2(FDCANHandler *Handler)
{
//初始化
Roughening_Motor_Controller_CAN2 = Handler;
Roughening_Motor_Controller_CAN2->CAN_Decode = Roughening_MotorDecodeCAN2;
HardWareErrorController->Add_PCOMHardWare(HardWareErrorController,"ZQ_CAN_ID3_SwingMotor", 1, ComError_ZQ_CAN_ID3_SwingMotor);
Roughening_DispacherController_CAN2 = Handler->dispacherController;
Roughening_DispacherController_CAN2->DispacherCallTime = 2;
Roughening_DispacherController_CAN2->Add_Dispatcher_List(Roughening_DispacherController_CAN2, MotorCommandsLoop_2_Position);
TT_Motor[3]=&GV.SwingMotor;
TT_Motor[3]->MotorID=3;
}
void MotorCommandsLoop()
{
//
// if(start_time<15000)
// {
// HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,"ZQ_CAN_ID1_LeftMotor", 1);
// HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,"ZQ_CAN_ID2_RightMotor", 1);
// }
GV.LeftMotor.Target_Velcity=(int)(GV.Left_Speed_M_min*Move_Base_Speed_Count_m_Min);
GV.RightMotor.Target_Velcity=(int)(GV.Right_Speed_M_min*Move_Base_Speed_Count_m_Min);
static int Heartbeat_Flag_01;
if (TT_Motor_Need_To_Activate == 1)
{
ActivateMotor(1, Roughening_Motor_Controller, 6000);
ActivateMotor(2, Roughening_Motor_Controller, 2000);
ActivateMotor(1, Roughening_Motor_Controller, 2000);
ActivateMotor(2, Roughening_Motor_Controller, 2000);
ActivateMotor(1, Roughening_Motor_Controller, 2000);
ActivateMotor(2, Roughening_Motor_Controller, 2000);
ActivateMotor(1, Roughening_Motor_Controller, 2000);
ActivateMotor(2, Roughening_Motor_Controller, 2000);
Enable_NMT(000,Roughening_Motor_Controller,01,1000);
Enable_NMT(000,Roughening_Motor_Controller,02,1000);
Configure_Asynchronous_Mode(1, Roughening_Motor_Controller, 7,600);
Consumer_Or_microcontroller_Heartbeat(0x707, Roughening_Motor_Controller, 4);
Configure_Asynchronous_Mode(2, Roughening_Motor_Controller, 8,600);
Consumer_Or_microcontroller_Heartbeat(0x707, Roughening_Motor_Controller, 4);
SpeedModeSetup(1, Roughening_Motor_Controller, 6, 500, 500, 0);
Consumer_Or_microcontroller_Heartbeat(0x708, Roughening_Motor_Controller, 4);
SpeedModeSetup(2, Roughening_Motor_Controller, 6, 500, 500, 0);
Consumer_Or_microcontroller_Heartbeat(0x707, Roughening_Motor_Controller, 4);
Consumer_Or_microcontroller_Heartbeat(0x708, Roughening_Motor_Controller, 4);
TT_Motor_Need_To_Activate = 0;
}
else
{
for (int i = 1; i < 3; i++)//前两个电机
{
TT_Request_Position(i, Roughening_Motor_Controller, 6);
TT_Request_Velocity(i, Roughening_Motor_Controller, 6);
TT_Request_Current(i, Roughening_Motor_Controller, 6);
TT_Request_Fault(i, Roughening_Motor_Controller, 6);
}
TT_SpeedMode_Set_TargetSpeed(1, Roughening_Motor_Controller, 6,GV.LeftMotor.Target_Velcity);
TT_SpeedMode_Set_TargetSpeed(2, Roughening_Motor_Controller, 6,GV.RightMotor.Target_Velcity);
}
Heartbeat_Flag_01++;
if(Heartbeat_Flag_01%7==0)
{
Consumer_Or_microcontroller_Heartbeat(0x707, Roughening_Motor_Controller, 4);
Consumer_Or_microcontroller_Heartbeat(0x708, Roughening_Motor_Controller, 4);
Heartbeat_Flag_01=0;
}
}
void MotorCommandsLoop_2_Position()
{
// if(start_time<15000)
// {
// HardWareErrorController->Set_PCOMHardWare(HardWareErrorController, "ZQ_CAN_ID3_SwingMotor", 1);
// }
GV.SwingMotor.Tar_Position_count=(int32_t)(middle_position_motor-GV.Tar_Position_angle*TT_One_Deg_Count_motor);
GV.SwingMotor.Tar_Position_Velcity_RPM=GV.Tar_Position_Velcity_Degree_S*Swing_Speed_Deg_Sencond_motor;
if (TT_Motor_Need_To_Activate_1 == 1)
{
ActivateMotor(3, Roughening_Motor_Controller_CAN2, 6000);
ActivateMotor(3, Roughening_Motor_Controller_CAN2, 2000);
ActivateMotor(3, Roughening_Motor_Controller_CAN2, 2000);
ActivateMotor(3, Roughening_Motor_Controller_CAN2, 2000);
ActivateMotor(3, Roughening_Motor_Controller_CAN2, 2000);
Postion_Velcocity_Run_SetParameter( 3, 0, 0, 500, 500, Roughening_Motor_Controller_CAN2, 100 );
TT_Motor_Need_To_Activate_1 = 0;
}
else
{
for (int i = 3; i <4 ; i++)//前两个电机
{
TT_Request_Position(3, Roughening_Motor_Controller_CAN2, 10);
TT_Request_Fault(3, Roughening_Motor_Controller_CAN2, 10);
}
switch(GV.SwingMotor.Position_immediately1_Lag2)
{
case 1:
Position_Immediately_Setting(3,Roughening_Motor_Controller_CAN2, GV.SwingMotor.Tar_Position_count,GV.SwingMotor.Tar_Position_Velcity_RPM,30);
break;
case 2:
Position_Lag_Setting(3,Roughening_Motor_Controller_CAN2, GV.SwingMotor.Tar_Position_count,GV.SwingMotor.Tar_Position_Velcity_RPM,30);
break;
}
}
}
void MotorCommandsLoop_2()
{
static int Heartbeat_Flag;
if (TT_Motor_Need_To_Activate_1 == 1)
{
ActivateMotor(3, Roughening_Motor_Controller_CAN2, 6000);
ActivateMotor(3, Roughening_Motor_Controller_CAN2, 2000);
ActivateMotor(3, Roughening_Motor_Controller_CAN2, 2000);
Enable_NMT(000,Roughening_Motor_Controller_CAN2,03,1000);
Configure_Asynchronous_Mode(3, Roughening_Motor_Controller_CAN2, 9,1000);
SpeedModeSetup(3, Roughening_Motor_Controller_CAN2, 12, 500, 500, 0);
TT_Motor_Need_To_Activate_1 = 0;
}
else
{
for (int i = 3; i <4 ; i++)//前两个电机
{
TT_Request_Position(3, Roughening_Motor_Controller_CAN2, 6);
TT_Request_Current(3, Roughening_Motor_Controller_CAN2, 6);
TT_Request_Fault(3, Roughening_Motor_Controller_CAN2, 6);
}
// TT_SpeedMode_Set_TargetSpeed(3, Roughening_Motor_Controller_CAN2, 6,GV.SwingMotor.Target_Velcity);
Heartbeat_Flag++;
if(Heartbeat_Flag%15==0)
{
Consumer_Or_microcontroller_Heartbeat(0x709, Roughening_Motor_Controller_CAN2, 4);
Heartbeat_Flag=0;
}
}
}
char a[10];
int32_t fluat_flag=0;
void Roughening_MotorDecodeCAN(uint32_t canID, uint8_t *buffer, uint32_t length)
{
memcpy(a,buffer,8);
switch (canID - 0x580)
{
case 1:
{
HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,"ZQ_CAN_ID1_LeftMotor", 1);
TT_Analytic_Fun(1, buffer);
}
break;
case 2:
{
HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,"ZQ_CAN_ID2_RightMotor", 1);
TT_Analytic_Fun(2, buffer);
}
break;
case 3:
{
fluat_flag=1;
}
break;
}
}
void Roughening_MotorDecodeCAN2(uint32_t canID, uint8_t *buffer, uint32_t length)
{
memcpy(a,buffer,8);
switch (canID - 0x580)
{
case 1:
{
fluat_flag=2;
}
break;
case 2:
{
fluat_flag=3;
}
break;
case 3:
{
HardWareErrorController->Set_PCOMHardWare(HardWareErrorController, "ZQ_CAN_ID3_SwingMotor", 1);
TT_Analytic_Fun(3, buffer);
}
break;
}
}

35
Bingoo/base/motors_power_action.c

@ -0,0 +1,35 @@
/*
* motors_power_action.c
*
* Created on: 2025714
* Author: akeguo
*/
#include "motors_power_action.h"
#include "motors.h"
transition_t current_motor_power_state;
transition_state_t motor_power_on_state={Motors_Power_On_Enter,Motors_Power_On_Do,Motors_Power_On_Exit};
transition_state_t motor_power_off_state={NULL,Motors_Power_Off_Do,NULL};
void Motors_Power_On_Do(transition_t *p_this)
{
GF_BSP_GPIO_SetIO(Motor_Power_IO_CTL, K_ON_Motor);
}
void Motors_Power_Off_Do(transition_t *p_this)
{
GF_BSP_GPIO_SetIO(Motor_Power_IO_CTL, K_OFF_Motor);
}
void Motors_Power_On_Enter(transition_t *p_this)
{
}
void Motors_Power_On_Exit(transition_t *p_this)
{
}

102
Bingoo/base/msp_DAM_Relay.c

@ -0,0 +1,102 @@
/*
* msp_DAM_Relay.c
*
* Created on: Nov 5, 2024
* Author: akeguo
*/
#include "../../BASE/Inc/MSP/msp_DAM_Relay.h"
#include "../../BASE/Inc/BSP/BHBF_ROBOT.h"
#include "../../BASE/Inc/BSP/bsp_MB_host.h"
//not modbus writcoil
uint8_t Dan1_open[8] = { 0xFE, 0x05, 0x00, 0x00, 0xFF, 0x00, 0x98, 0x35 };
uint8_t Dan1_close[8] = { 0xFE, 0x05, 0x00, 0x00, 0x00, 0x00, 0xD9, 0xC5 };
uint8_t Dan2_open[8] = { 0xFE, 0x05, 0x00, 0x01, 0xFF, 0x00, 0xC9, 0xF5 };
uint8_t Dan2_close[8] = { 0xFE, 0x05, 0x00, 0x01, 0x00, 0x00, 0x88, 0x05 };
uint8_t Dan3_open[8] = { 0xFE, 0x05, 0x00, 0x02, 0xFF, 0x00, 0x39, 0xF5 };
uint8_t Dan3_close[8] = { 0xFE, 0x05, 0x00, 0x02, 0x00, 0x00, 0x78, 0x05 };
uint8_t Dan4_open[8] = { 0xFE, 0x05, 0x00, 0x03, 0xFF, 0x00, 0x68, 0x35 };
uint8_t Dan4_close[8] = { 0xFE, 0x05, 0x00, 0x03, 0x00, 0x00, 0x29, 0xC5 };
int32_t DMA_DO_Value_[4];//DAM模块
void decode_DAM(uint8_t *buffer, uint16_t length);
void DAM_0_Set();
void DAM_1_Set();
void DAM_2_Set();
void DAM_3_Set();
struct UARTHandler *DAM_Relay;
DispacherController *DAM_Relay_dispacherController;
void DAM_Relay_intialize(struct UARTHandler *Handler) {
//uartHandler_intialize(&Force_sensor,Handler,10);
DAM_Relay = Handler;
DAM_Relay->UART_Decode = decode_DAM;
DAM_Relay->Wait_time = 6; //等待10ms 最低不要低于4;
DAM_Relay_dispacherController = Handler->dispacherController;
DAM_Relay_dispacherController->DispacherCallTime = 200; //10 是100ms 难道这个2ms的定时器是10ms的?
LOG("DAM intialize");
DAM_Relay_dispacherController->Dispacher_Enable = 1;
//log_info("angle_encoder_intialize");
DAM_Relay_dispacherController->Add_Dispatcher_List(
DAM_Relay_dispacherController, DAM_0_Set);
DAM_Relay_dispacherController->Add_Dispatcher_List(
DAM_Relay_dispacherController, DAM_1_Set);
DAM_Relay_dispacherController->Add_Dispatcher_List(
DAM_Relay_dispacherController, DAM_2_Set);
DAM_Relay_dispacherController->Add_Dispatcher_List(
DAM_Relay_dispacherController, DAM_3_Set);
}
void DAM_0_Set() {
if (DMA_DO_Value_[0] == 1) {
memcpy(&DAM_Relay->Tx_Buf, &Dan1_open, 8);
} else {
memcpy(&DAM_Relay->Tx_Buf, &Dan1_close, 8);
}
DAM_Relay->TxCount = 8;
DAM_Relay->UART_Tx(DAM_Relay); //send the data from the modbus command;
}
void DAM_1_Set() {
if (DMA_DO_Value_[1] == 1) {
memcpy(&DAM_Relay->Tx_Buf, &Dan2_open, 8);
} else {
memcpy(&DAM_Relay->Tx_Buf, &Dan2_close, 8);
}
DAM_Relay->TxCount = 8;
DAM_Relay->UART_Tx(DAM_Relay); //send the data from the modbus command;
}
void DAM_2_Set() {
if (DMA_DO_Value_[2] == 1) {
memcpy(&DAM_Relay->Tx_Buf, &Dan3_open, 8);
} else {
memcpy(&DAM_Relay->Tx_Buf, &Dan3_close, 8);
}
DAM_Relay->TxCount = 8;
DAM_Relay->UART_Tx(DAM_Relay); //send the data from the modbus command;
}
void DAM_3_Set() {
if (DMA_DO_Value_[3] == 1) {
memcpy(&DAM_Relay->Tx_Buf, &Dan4_open, 8);
} else {
memcpy(&DAM_Relay->Tx_Buf, &Dan4_close, 8);
}
DAM_Relay->TxCount = 8;
DAM_Relay->UART_Tx(DAM_Relay); //send the data from the modbus command;
}
void decode_DAM(uint8_t *buffer, uint16_t length) {
/* CRC 校验 */
uint16_t crc_check = ((buffer[length - 1] << 8) | buffer[length - 2]);
/* CRC 校验正确 */
if (crc_check == MB_CRC16(buffer, length - 2)) {
HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,
"DAM", 1);
} else {
}
}

12
Bingoo/base/msp_MK32.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "msp_MK32.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(SP_MSP_MK32_Button, SP_MSP_MK32_Button, AUTO)

118
Bingoo/base/msp_MK32_1.c

@ -0,0 +1,118 @@
/*
* msp_MK32_1.c
*
* Created on: Oct 8, 2024
* Author: akeguo
*/
#include "MSP/msp_MK32_1.h"
#include "BHBF_ROBOT.h"
char Is_All_Button_Reset = 0;
SP_MSP_MK32_Button *P_MK32;
struct UARTHandler *MK32_Sbus_Controller;
void decode_MK32Data(uint8_t *buffer, uint16_t length)
{
if (length != 25)
{
return;
}
if (buffer[0] == 0X0f && buffer[24] == 0X00)
{
Sbus_Data_Count(&buffer[1], (int32_t*) (P_MK32));
}
// int32_t RxIndex;
// int32_t CH0_RY_H; /* 上1000,下-1000 */
// int32_t CH1_RY_V; /* 上1000,下-1000 */
// int32_t CH2_LY_V; /* 上1000,下-1000 */
// int32_t CH3_LY_H; /* 上1000,下-1000 */
// int32_t CH4_SA; /* 上-1000,下1000 */
// int32_t CH5_SB; /* 上-1000,下1000 */
// int32_t CH6_SC; /* 上-1000,下1000 */
// int32_t CH7_SD; /* 上-1000,下1000 */
// int32_t CH8_SE; /* 上-1000,下1000 */
// int32_t CH9_SF; /* 上-1000,下1000 */
// int32_t CH10_LD1;
// int32_t CH11_RD1;
// int32_t CH12_S1;
// int32_t CH13_S2;
// int32_t CH14_LT;
// int32_t CH15_RT;
// int32_t IsOnline;
if (Is_All_Button_Reset == 0)
{
if (P_MK32->CH4_SA == 0 && P_MK32->CH5_SB == 0 && P_MK32->CH6_SC == 0
&& P_MK32->CH7_SD == 0 && P_MK32->IsOnline == 1)
{
HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,
"Need_To_Reset", 1);
Is_All_Button_Reset = 1;
}
}
else if (Is_All_Button_Reset == 1)
{
HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,
"Need_To_Reset", 1);
}
HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,
"mk32_sbus", 1);
}
void Sbus_Data_Count(uint8_t *buf, int32_t *But_Value)
{
int16_t CH[16];
int Start_byte = -1;
CH[0] = ((buf[Start_byte + 1] | buf[Start_byte + 2] << 8) & 0x07FF);
CH[1] = ((buf[Start_byte + 2] >> 3 | buf[Start_byte + 3] << 5) & 0x07FF);
CH[2] = ((buf[Start_byte + 3] >> 6 | buf[Start_byte + 4] << 2
| buf[Start_byte + 5] << 10) & 0x07FF);
CH[3] = ((buf[Start_byte + 5] >> 1 | buf[Start_byte + 6] << 7) & 0x07FF);
CH[4] = ((buf[Start_byte + 6] >> 4 | buf[Start_byte + 7] << 4) & 0x07FF);
CH[5] = ((buf[Start_byte + 7] >> 7 | buf[Start_byte + 8] << 1
| buf[Start_byte + 9] << 9) & 0x07FF);
CH[6] = ((buf[Start_byte + 9] >> 2 | buf[Start_byte + 10] << 6) & 0x07FF);
CH[7] = ((buf[Start_byte + 10] >> 5 | buf[Start_byte + 11] << 3) & 0x07FF);
CH[8] = ((buf[Start_byte + 12] | buf[Start_byte + 13] << 8) & 0x07FF);
CH[9] = ((buf[Start_byte + 13] >> 3 | buf[Start_byte + 14] << 5) & 0x07FF);
CH[10] = ((buf[Start_byte + 14] >> 6 | buf[Start_byte + 15] << 2
| buf[Start_byte + 16] << 10) & 0x07FF);
CH[11] = ((buf[Start_byte + 16] >> 1 | buf[Start_byte + 17] << 7) & 0x07FF);
CH[12] = ((buf[Start_byte + 17] >> 4 | buf[Start_byte + 18] << 4) & 0x07FF);
CH[13] = ((buf[Start_byte + 18] >> 7 | buf[Start_byte + 19] << 1
| buf[Start_byte + 20] << 9) & 0x07FF);
CH[14] = ((buf[Start_byte + 20] >> 2 | buf[Start_byte + 21] << 6) & 0x07FF);
CH[15] = ((buf[Start_byte + 21] >> 5 | buf[Start_byte + 22] << 3) & 0x07FF);
//按键数值:1050为中间值,272-1712
for (int i = 0; i < 16; i++)
{
But_Value[i + 1] = (int32_t) ((CH[i] - 992) * 1.388889);
}
//遥控器地面站在线状态
if (buf[22] == 0) But_Value[17] = 1;
else
But_Value[17] = 0;
But_Value[0]++;
}
void MK32_Sbus_UART_Handler_intialize(struct UARTHandler *Handler)
{
MK32_Sbus_Controller = Handler;
MK32_Sbus_Controller->UART_Decode = decode_MK32Data;
MK32_Sbus_Controller->Wait_time = 4;
MK32_Sbus_Controller->dispacherController->Dispacher_Enable = 0; //不周期性发送
HardWareErrorController->Add_PCOMHardWare(HardWareErrorController,
"Need_To_Reset", 0, ComError_MK32_InitialState);
HardWareErrorController->Add_PCOMHardWare(HardWareErrorController,
"mk32_sbus", 0, ComError_Mk32_SBus);
LOG("MK32_Sbus_intialize");
}

12
Bingoo/base/msp_Motor.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "msp_Motor.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(MotorParameters, MotorParameters, AUTO)

256
Bingoo/base/msp_PID.c

@ -0,0 +1,256 @@
/*
* msp_PID.c - PIDfloat版本
*/
#include "msp_PID.h"
#include <math.h>
#include <float.h>
// ========== 内置固定参数 ==========
#define CONTROL_DT 0.1f // 固定采样时间 0.1秒
#define MAX_SPEED_FACTOR 1.6f // 最大速度 = 基础速度 * 1.6
// ========== 全局可调参数 ==========
float PID_KP = 0.5f; // 比例系数
float PID_KD = 0.012f; // 微分系数
float PID_KP_WELD = 0.1f; // 比例系数
float PID_KD_WELD = 0.025f; // 微分系数
float Kp1 = 1.0f; // 小角度增益因子
float Kp2 = 0.95f; // 中小角度增益因子
float Kp3 = 0.80f; // 中大角度增益因子
float Kp4 = 0.50f; // 大角度增益因子
double Desire_Angle = 0; //用于焊缝跟踪的期望角度
// 误差分段阈值(度)
static const float ANGLE_THRESHOLD1 = 2.0f;
static const float ANGLE_THRESHOLD2 = 5.0f;
static const float ANGLE_THRESHOLD3 = 10.0f;
// ========== 内部静态变量 ==========
static float last_error = 0.0f; // 上一次误差(用于微分)
// ========== 内部函数声明 ==========
static float normalize_angle(float angle);
static float compute_pd_output(float error,float KP,float KD);
static float get_gain_factor(float abs_error);
void Weld_PID(double CurrentValue, double TargetValue, double Sys_T,
double *Gain_speed);
void GF_MSP_PID_Now_Der_adj_Com_Weld(double Current_Angle, double Desire_Angle_Input,
double Auto_Speed, double Auto_Speed_Max, double System_time, double *W_Speed_1);
// ========== 函数实现 ==========
/* 将角度归一化到 [-180, 180) */
static float normalize_angle(float angle)
{
while (angle >= 180.0f) angle -= 360.0f;
while (angle < -180.0f) angle += 360.0f;
return angle;
}
/* PD控制器:输入误差,输出控制增量(使用固定 dt = CONTROL_DT) */
static float compute_pd_output(float error,float KP,float KD)
{
float p_term = KP * error;
float d_term = KD * (error - last_error) / CONTROL_DT;
last_error = error;
return p_term + d_term;
}
/* 根据误差绝对值选择增益因子 */
static float get_gain_factor(float abs_error)
{
if (abs_error <= ANGLE_THRESHOLD1) return Kp1;
if (abs_error <= ANGLE_THRESHOLD2) return Kp2;
if (abs_error <= ANGLE_THRESHOLD3) return Kp3;
return Kp4;
}
/* 两轮差速角度控制(对外接口) */
void TwoWheel_AngleControl(float current_angle, float desired_angle,
float base_speed,float zoom, float speeds[2])
{
// 1. 计算归一化误差
float raw_error = desired_angle - current_angle;
float error = normalize_angle(raw_error);
float abs_error = fabsf(error);
// 2. PD控制量
float delta = zoom*compute_pd_output(error,PID_KP,PID_KD);
// 3. 根据误差大小选择增益因子
float factor = get_gain_factor(abs_error);
// 4. 计算左右轮速度
float left = base_speed + factor * delta;
float right = base_speed - factor * delta;
// 5. 内置最大速度 = 1.6 * |base_speed|
float max_speed = fabsf(base_speed) * MAX_SPEED_FACTOR;
// 6. 限幅:等比缩放至最大速度以内
float max_abs = fmaxf(fabsf(left), fabsf(right));
if (max_abs > max_speed && max_abs > FLT_MIN) {
float scale = max_speed / max_abs;
left *= scale;
right *= scale;
}
speeds[0] = left;
speeds[1] = right;
}
/* 两轮差速角度控制(对外接口) */
void TwoWheel_AngleControl_Weld(float current_angle, float desired_angle,
float base_speed,float zoom, float speeds[2])
{
// 1. 计算归一化误差
float raw_error = desired_angle - current_angle;
float error = normalize_angle(raw_error);
float abs_error = fabsf(error);
// 2. PD控制量
float delta = zoom*compute_pd_output(error,PID_KP_WELD,PID_KD_WELD);
// 3. 根据误差大小选择增益因子
float factor = get_gain_factor(abs_error);
// 4. 计算左右轮速度
float left = base_speed + factor * delta;
float right = base_speed - factor * delta;
// 5. 内置最大速度 = 1.6 * |base_speed|
float max_speed = fabsf(base_speed) * MAX_SPEED_FACTOR;
// 6. 限幅:等比缩放至最大速度以内
float max_abs = fmaxf(fabsf(left), fabsf(right));
if (max_abs > max_speed && max_abs > FLT_MIN) {
float scale = max_speed / max_abs;
left *= scale;
right *= scale;
}
speeds[0] = left;
speeds[1] = right;
}
void GF_MSP_PID_Now_Der_adj_Com_Weld(double Current_Angle, double Desire_Angle_Input, double Auto_Speed, double Auto_Speed_Max, double System_time, double *W_Speed_1)
{
Desire_Angle = Desire_Angle_Input;
//水平 前进抬车头
double Detal_Angle = fabs(Current_Angle - Desire_Angle);
double Incre_Speed[1];
Weld_PID(Current_Angle, Desire_Angle, System_time, Incre_Speed);
Incre_Speed[0] = 8 * Incre_Speed[0];
double deltaAngle1 = 0.2;
double deltaAngle2 = 5;
double deltaAngle3 = 10;
//double deltaAngle4=25;
double LeftSpeed_Con_1;
double RightSpeed_Con_1;
double LeftSpeed_Con_2;
double RightSpeed_Con_2;
LeftSpeed_Con_1 = (Auto_Speed + Kp1 * Incre_Speed[0]);
RightSpeed_Con_1 = (Auto_Speed - Kp1 * Incre_Speed[0]);
LeftSpeed_Con_2 = Auto_Speed + Kp1 * Incre_Speed[0];
RightSpeed_Con_2 = Auto_Speed - Kp1 * Incre_Speed[0];
// if (Detal_Angle >= deltaAngle1)
// {
//
////小角度时,两前轮调整
// }
// else if (Detal_Angle > deltaAngle1 && Detal_Angle <= deltaAngle2)
// {
// LeftSpeed_Con_1 = (Auto_Speed + Kp2 * Incre_Speed[0]);
// RightSpeed_Con_1 = (Auto_Speed - Kp2 * Incre_Speed[0]);
// LeftSpeed_Con_2 = Auto_Speed + Kp2 * Incre_Speed[0];
// RightSpeed_Con_2 = Auto_Speed - Kp2 * Incre_Speed[0];
////中小角度时,两前轮差速,两后轮跟踪调整
// }
// else if (Detal_Angle > deltaAngle2 && Detal_Angle <= deltaAngle3)
// {
// LeftSpeed_Con_1 = (Auto_Speed + Kp3 * Incre_Speed[0]);
// RightSpeed_Con_1 = (Auto_Speed - Kp3 * Incre_Speed[0]);
// LeftSpeed_Con_2 = Auto_Speed + Kp3 * Incre_Speed[0];
// RightSpeed_Con_2 = Auto_Speed - Kp3 * Incre_Speed[0];
// }
// else
// {
// LeftSpeed_Con_1 = (Auto_Speed + Kp4 * Incre_Speed[0]);
// RightSpeed_Con_1 = (Auto_Speed - Kp4 * Incre_Speed[0]);
// LeftSpeed_Con_2 = Auto_Speed + Kp4 * Incre_Speed[0];
// RightSpeed_Con_2 = Auto_Speed - Kp4 * Incre_Speed[0];
// }
double Jud_value = fabs(LeftSpeed_Con_1) - fabs(RightSpeed_Con_1);
double factor = 0;
if (Jud_value >= 0)
{
if (LeftSpeed_Con_1 > Auto_Speed_Max)
{
factor = Auto_Speed_Max / LeftSpeed_Con_1;
LeftSpeed_Con_1 = Auto_Speed_Max;
LeftSpeed_Con_2 = LeftSpeed_Con_2 * factor;
RightSpeed_Con_1 = RightSpeed_Con_1 * factor;
RightSpeed_Con_2 = RightSpeed_Con_2 * factor;
}
else if (LeftSpeed_Con_1 < -Auto_Speed_Max)
{
factor = -Auto_Speed_Max / LeftSpeed_Con_1;
LeftSpeed_Con_1 = -Auto_Speed_Max;
LeftSpeed_Con_2 = LeftSpeed_Con_2 * factor;
RightSpeed_Con_1 = RightSpeed_Con_1 * factor;
RightSpeed_Con_2 = RightSpeed_Con_2 * factor;
}
}
else
{
if (RightSpeed_Con_1 > Auto_Speed_Max)
{
factor = Auto_Speed_Max / RightSpeed_Con_1;
RightSpeed_Con_1 = Auto_Speed_Max;
RightSpeed_Con_2 = RightSpeed_Con_2 * factor;
LeftSpeed_Con_1 = LeftSpeed_Con_1 * factor;
LeftSpeed_Con_2 = LeftSpeed_Con_2 * factor;
}
else if (LeftSpeed_Con_2 < -Auto_Speed_Max)
{
factor = -Auto_Speed_Max / RightSpeed_Con_1;
RightSpeed_Con_1 = -Auto_Speed_Max;
RightSpeed_Con_2 = RightSpeed_Con_2 * factor;
LeftSpeed_Con_1 = LeftSpeed_Con_1 * factor;
LeftSpeed_Con_2 = LeftSpeed_Con_2 * factor;
}
}
W_Speed_1[0] = LeftSpeed_Con_1;
W_Speed_1[1] = RightSpeed_Con_1;
W_Speed_1[2] = LeftSpeed_Con_2;
W_Speed_1[3] = RightSpeed_Con_2;
}
double Weld_KP = 10;
double Weld_KD = 10;
//double Sys_T=0.01;//System time
double Weld_1_error = 0;
void Weld_PID(double CurrentValue, double TargetValue, double Sys_T,
double *Gain_speed)
{
double Error;
double P_Error;
double D_Error;
Error = TargetValue - CurrentValue;
P_Error = Error;
D_Error = Error - Weld_1_error;
Weld_1_error = Error;
Gain_speed[0] = Weld_KP * P_Error + Weld_KD * D_Error / Sys_T;
}

100
Bingoo/base/msp_TL720D.c

@ -0,0 +1,100 @@
/*
* msp_TL720D.c
*
* Created on: Jul 19, 2024
* Author: bihon
*/
#include "MSP/msp_TL720D.h"
#include "BHBF_ROBOT.h"
#include "msp_TL720D.pb.h"
//Roll:0.01°
int32_t *RobotAngle;
struct UARTHandler *TL720D_UART_Handler;
MSP_TL720DParameters* SP_MSP_RF_TL720D_Parameters_In;
void decode_TL720D(uint8_t *buffer, uint16_t length);
int16_t getDeci(uint8_t *data);
void TL720D_intialize(struct UARTHandler *Handler)
{
//TL720D_UART_Handler->UART_Decode = NULL;
TL720D_UART_Handler = Handler;
TL720D_UART_Handler->Wait_time=6;
TL720D_UART_Handler->dispacherController->Dispacher_Enable=0;//不周期性发送
TL720D_UART_Handler->UART_Decode = decode_TL720D;
HardWareErrorController->Add_PCOMHardWare(HardWareErrorController,"TL720D",0,ComError_TL720D);
//log_info("TL720D_intialize");
LOGFF(DL_ERROR,"TL720D_intialize");
}
void decode_TL720D(uint8_t *buffer, uint16_t length)
{
if (buffer[0] == 0x68 && buffer[1] == 0x1F && buffer[2] == 0x00
&& buffer[3] == 0x84)
{
//SP_MSP_RF_TL720D_Parameters_In.
SP_MSP_RF_TL720D_Parameters_In->RF_Angle_Roll = getDeci(&buffer[4]);
SP_MSP_RF_TL720D_Parameters_In->RF_Angle_Pitch = getDeci(&buffer[7]);
SP_MSP_RF_TL720D_Parameters_In->RF_Angle_Yaw = getDeci(&buffer[10]);
SP_MSP_RF_TL720D_Parameters_In->RF_Acc_X = getDeci(&buffer[13]);
SP_MSP_RF_TL720D_Parameters_In->RF_Acc_Y = getDeci(&buffer[16]);
SP_MSP_RF_TL720D_Parameters_In->RF_Acc_Z = getDeci(&buffer[19]);
SP_MSP_RF_TL720D_Parameters_In->RF_Gro_X = getDeci(&buffer[22]);
SP_MSP_RF_TL720D_Parameters_In->RF_Gro_Y = getDeci(&buffer[25]);
SP_MSP_RF_TL720D_Parameters_In->RF_Gro_Z = getDeci(&buffer[28]);
LOG("TL720D decoding succeeded");
*RobotAngle=SP_MSP_RF_TL720D_Parameters_In->RF_Angle_Roll;
//Is_TL720_Updating_Flag=true;
HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,"TL720D",1);
} else
{
//log_error("TL720D decoding failed");
LOGFF(DL_ERROR,"TL720D decoding failed");
}
}
/* 数值计算
* data:
* return: : 0.01
* */
int16_t getDeci(uint8_t *data)
{
char isNegative = 0;
if (*data >> 4)
{
isNegative = 1;
} else
{
isNegative = 0;
}
int16_t data_value = 0;
data_value = ((*data) & 0x0f) * 10000;
data++;
data_value += (*data >> 4) * 1000;
data_value += ((*data) & 0x0f) * 100;
data++;
int16_t xiaoshu = 0;
xiaoshu = (*data >> 4) * 10;
xiaoshu += (*data) & 0x0f;
if (isNegative)
{
return -(data_value + xiaoshu);
} else
{
return (data_value + xiaoshu);
}
}

12
Bingoo/base/msp_TL720D.pb.c

@ -0,0 +1,12 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "msp_TL720D.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(MSP_TL720DParameters, MSP_TL720DParameters, AUTO)

426
Bingoo/base/msp_TTMotor_ZQ.c

@ -0,0 +1,426 @@
/*
* msp_TTMotor_ZQ.c
*
* Created on: Oct 10, 2024
* Author: akeguo
*/
#include "msp_TTMotor_ZQ.h"
#include "BHBF_ROBOT.h"
TT_MotorParameters *TT_Motor[7];
void ActivateMotor(int32_t MotorID, FDCANHandler *ZQ_Motor_Controller,
int32_t WaitTime)
{
ZQ_Motor_Controller->Tx_Buf[0] = 0x10;
ZQ_Motor_Controller->Tx_Buf[1] = 0x10;
ZQ_Motor_Controller->AddCANSendList(ZQ_Motor_Controller, MotorID, 2,
ZQ_Motor_Controller->Tx_Buf, WaitTime, NULL); //wait for 5 seconds to send
//CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x6083, 0x00, AccTime,ZQ_Motor_Controller,WaitTime);
}
void Enable_NMT(int32_t MotorID, FDCANHandler *ZQ_Motor_Controller, int32_t Node_Number, int32_t WaitTime)
{
ZQ_Motor_Controller->Tx_Buf[0] = 0x01;
ZQ_Motor_Controller->Tx_Buf[1] = Node_Number;
ZQ_Motor_Controller->AddCANSendList(ZQ_Motor_Controller, MotorID, 2, ZQ_Motor_Controller->Tx_Buf, WaitTime, NULL); //wait for 5 seconds to send
}
void Configure_Asynchronous_Mode(int32_t MotorID, FDCANHandler *ZQ_Motor_Controller, int32_t Node_Number, int32_t WaitTime)
{
ZQ_Motor_Controller->Tx_Buf[0] = 0x23;
ZQ_Motor_Controller->Tx_Buf[1] = 0x16;
ZQ_Motor_Controller->Tx_Buf[2] = 0x10;
ZQ_Motor_Controller->Tx_Buf[3] = 0x01;
ZQ_Motor_Controller->Tx_Buf[4] = 0xe8;
ZQ_Motor_Controller->Tx_Buf[5] = 0x03;
ZQ_Motor_Controller->Tx_Buf[6] = Node_Number;
ZQ_Motor_Controller->Tx_Buf[7] = 0x00;
ZQ_Motor_Controller->AddCANSendList(ZQ_Motor_Controller, 0x600 + MotorID, 8, ZQ_Motor_Controller->Tx_Buf, WaitTime, NULL);
}
void Consumer_Or_microcontroller_Heartbeat(int32_t MotorID, FDCANHandler *ZQ_Motor_Controller, int32_t WaitTime)
{
ZQ_Motor_Controller->Tx_Buf[0] = 0x05;
ZQ_Motor_Controller->AddCANSendList(ZQ_Motor_Controller, MotorID, 1, ZQ_Motor_Controller->Tx_Buf, WaitTime, NULL); //wait for 5 seconds to send
}
void CANSendMessageSDO_ADD_To_SendList(int32_t MotorID, uint8_t Function,
uint16_t ControlWord, uint8_t subWord, int32_t ControlWordValue,
FDCANHandler *ZQ_Motor_Controller, int32_t WaitTime)
{
//copy the corresponsiding data to the send Array
ZQ_Motor_Controller->Tx_Buf[0] = Function;
memcpy(&ZQ_Motor_Controller->Tx_Buf[1], &ControlWord, 2);
ZQ_Motor_Controller->Tx_Buf[3] = subWord;
memcpy(&ZQ_Motor_Controller->Tx_Buf[4], &ControlWordValue, 4);
//send 8 bytes data
ZQ_Motor_Controller->AddCANSendList(ZQ_Motor_Controller, 0x600 + MotorID, 8,
ZQ_Motor_Controller->Tx_Buf, WaitTime, NULL);
}
//位置速度模式
void Postion_Velcocity_Run_SetParameter(int32_t MotorID, int32_t TargetPosition,
int32_t TargetSpeed, int32_t AccTime, int32_t DecTime,
FDCANHandler *ZQ_Motor_Controller, int32_t WaitTime)
{
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2f, 0x6060, 0x00, 1,
ZQ_Motor_Controller, WaitTime); // 1:设置操作模式,向索引0x6060:00写入0x01
if (TargetSpeed >= 3500) //the highest is 3500
{
TargetSpeed = 3500;
}
if (TargetSpeed < 0)
{
TargetSpeed = 0;
}
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x6083, 0x00, AccTime,
ZQ_Motor_Controller, WaitTime); //2:设置加速时间,向索引0x6083:00写入4字节数值
// Thread.Sleep(2);
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x6084, 0x00, DecTime,
ZQ_Motor_Controller, WaitTime); //3:设置减速时间,向索引0x6084:00写入4字节数值
//Thread.Sleep(2);
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x607A, 0x00,
TargetPosition, ZQ_Motor_Controller, WaitTime); //4:设置目标位置,向索引 0x607A:00写入4字节数值
// Thread.Sleep(2);
//23:写4字节数据;
//816000:索引号为0x6081,子索引号为0x00;
//E80300 00:设置运行速度为1000(单位0.1rpm)
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x6081, 0x00,
TargetSpeed * 10, ZQ_Motor_Controller, WaitTime); //5:设置运行速度,向索引 0x6081:00写入4字节数值
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x80,
ZQ_Motor_Controller, WaitTime); ///6:清除异常,向控制字0x6040:00写入0x80
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x06,
ZQ_Motor_Controller, WaitTime); //7:伺服准备,向控制字 0x6040:00写入0x06
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x07,
ZQ_Motor_Controller, WaitTime); //8:伺服等待使能,向控制字0x6040:00写入0x07
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x2f,
ZQ_Motor_Controller, WaitTime); //9:伺服使能,向控制字0x6040:00写入0x0F
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x3f,
ZQ_Motor_Controller, WaitTime); //10:伺服启动,向控制字 0x6040:00写入0x1F ///:
}
void Postion_Velcocity_Set_Position(int32_t MotorID, int32_t TargetPosition,
FDCANHandler *ZQ_Motor_Controller, int32_t WaitTime)
{
// 3、立即更新时,重复执行步骤4、步骤9(控制字(6040)写入2F)和步骤10(控制字(6040)
// 写入3F),驱动器还没到达当前目标位置时,支持接收新的目标位置,最终到达的目标位
// 置是:新的目标位置。
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x607a, 0x00,
TargetPosition, ZQ_Motor_Controller, WaitTime); //设置目标位置
//Thread.Sleep(2);
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x2f,
ZQ_Motor_Controller, WaitTime); ///:
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x3f,
ZQ_Motor_Controller, WaitTime); ///:
}
void Driver_ReadError(int32_t MotorID, FDCANHandler *ZQ_Motor_Controller,
int32_t WaitTime)
{
//CANSendMessageSDO_ADD_To_SendList(CAN_ID, new byte[8] { 0x40, 0x0A, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00 });//40 0A 30 00 00 00 00 00
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x40, 0x300a, 0x00, 0,
ZQ_Motor_Controller, WaitTime); //40 0A 30 00 00 00 00 00
}
void SetMotorTargetPosition(int32_t MotorID, int32_t TargetPosition,
FDCANHandler *ZQ_Motor_Controller, int32_t WaitTime)
{
Postion_Velcocity_Set_Position(MotorID, TargetPosition, ZQ_Motor_Controller,
WaitTime);
}
void Postion_Velcocity_Stop(int32_t MotorID, FDCANHandler *ZQ_Motor_Controller,
int32_t WaitTime)
{
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6085, 0x00, 200,
ZQ_Motor_Controller, WaitTime); // 6085 的减速时间100ms
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x605a, 0x00, 6,
ZQ_Motor_Controller, WaitTime); // 0x06:按索引 6085 的减速时间进行减速,停下时电机 轴处于锁轴状态。
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x02,
ZQ_Motor_Controller, WaitTime); //快速停机
}
//void SetCurrentPositionZero(int32_t MotorID,FDCANHandler *ZQ_Motor_Controller,int32_t WaitTime)
//{
// CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2f, 0x6098, 0x00, 0x23,ZQ_Motor_Controller,WaitTime); //1:设置定位的方式,向索 引0x6098:00写入0X23
// CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2f, 0x6060, 0x00, 6,ZQ_Motor_Controller,WaitTime); //2:设置操作模式,向索引0x6060:00写入0x06
// CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x80,ZQ_Motor_Controller,WaitTime); //3:清除异常,向控制字 0x6040:00写入0x80
// CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x06,ZQ_Motor_Controller,WaitTime); //4:伺服准备,向控制字 0x6040:00写入0x06
// CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x07,ZQ_Motor_Controller,WaitTime); //5:伺服等待使能,向控制字0x6040:00写入0x07
// CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x0F,ZQ_Motor_Controller,WaitTime); //6:伺服使能,向控制字0x6040:00写入0x0F
// CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2f, 0x6040, 0x00, 0x1F,ZQ_Motor_Controller,WaitTime); //7:启动原点定位,向控制字0x6040:00写入0x1F
//}
void SpeedModeSetup(int32_t MotorID, FDCANHandler *ZQ_Motor_Controller,
int32_t WaitTime, int32_t Acc, int32_t Dec, int32_t TargetVelocity) //设定速度模式,并更改相关速度
{
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x02,
ZQ_Motor_Controller, 100);
//设置操作模式,向索引0x6060:00写入0x03
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2f, 0x6060, 0x00, 0x3,
ZQ_Motor_Controller, WaitTime);
//2:清除异常, 向控制字 0x6040:00 写入 0x80
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x80,
ZQ_Motor_Controller, WaitTime);
//3: 伺服准备, 向控制字 0x6040:00 写入 0x06
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x06,
ZQ_Motor_Controller, WaitTime);
//4: 伺服等待使能, 向控制字 0x6040:00 写入 0x07
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x07,
ZQ_Motor_Controller, WaitTime);
//5: 伺服使能,向控制字0x6040:00 写入 0x0F
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x0f,
ZQ_Motor_Controller, WaitTime);
//6:设置加速时间, 向索引 0x201C:00写入4字节数值 //不关心加速时间的模式下, 加减速时间建议设置为 1500(ms) 以上
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x201c, 0x00, Acc,
ZQ_Motor_Controller, WaitTime);
//7: 设置减速时间, 向索引0x201D:00写入4字节数据
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x201d, 0x00, Dec,
ZQ_Motor_Controller, WaitTime);
//8: 设定目标速度值, 向索引 0x60FF:00 写入 4 字节数值(有符号)
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x60ff, 0x00,
TargetVelocity, ZQ_Motor_Controller, WaitTime); ///6:清除异常,向控制字
//修改步骤8 可以实现速度的改变
// 23:写 4 字节数据;FF 60 00:索引号为 0x60FF,
// 子索引号为 0x00;E8 03 00 00:
// 设置目标速度 1000(单位 0.1rpm)
}
void TT_SpeedMode_Set_TargetSpeed(uint32_t MotorID,
FDCANHandler *ZQ_Motor_Controller, int32_t WaitTime,
int32_t TargetSpeed)
{
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x60ff, 0x00, TargetSpeed,
ZQ_Motor_Controller, WaitTime);
}
void Swing_Motor_Set_Target_Position()
{
CANSendMessageSDO(SwingMotorID, 0x40, 0x6041, 0x00, 0x00); ///:是否到达目的位置
}
void Swing_Motor_Read_ReachedEnd()
{
CANSendMessageSDO(SwingMotorID, 0x40, 0x6041, 0x00, 0x00); ///:是否到达目的位置
}
void Set_Current_Positon_Zero(uint8_t MotorID,
FDCANHandler *ZQ_Motor_Controller, int32_t WaitTime) // Home 设置当前位置为零点
{
// CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x2f,ZQ_Motor_Controller,WaitTime); ///:
// CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x3f,ZQ_Motor_Controller,WaitTime); ///:
//CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x2008, 0x00, 0x01,ZQ_Motor_Controller,1000);
//CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x02,ZQ_Motor_Controller,100); //1. 停止执行
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2f, 0x6098, 0x00, 0x23,
ZQ_Motor_Controller, WaitTime); //1. 设置定位的方式,向索引0x6098:00写入0X23
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2f, 0x6060, 0x00, 0x06,
ZQ_Motor_Controller, WaitTime); //2:设置操作模式,向索引0x6060:00写入0x06
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x80,
ZQ_Motor_Controller, WaitTime); //3:清除异常,向控制字0x6040:00写入0x80
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x06,
ZQ_Motor_Controller, WaitTime); //4.伺服准备,向控制字0x6040:00写入0x06
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x07,
ZQ_Motor_Controller, WaitTime); //5. 伺服等待使能,向控制字0x6040:00写入0x07
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x0f,
ZQ_Motor_Controller, WaitTime); //6. 伺服使能 向控制字 0x6040:00写入0x0F
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2f, 0x6040, 0x00, 0x1f,
ZQ_Motor_Controller, WaitTime); //7. :启动原点定位,向控制字0x6040:00写入0x1F
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x40, 0x6041, 0x00, 0x0,
ZQ_Motor_Controller, 100); //8. :启动原点定位,向控制字0x6040:00写入0x1F
}
void TT_Request_Position(uint32_t Motor_ID_1, FDCANHandler *ZQ_Motor_Controller,
int32_t WaitTime) // Home 设置当前位置为零点
{
CANSendMessageSDO_ADD_To_SendList(Motor_ID_1, 0x40, 0x6064, 0x00, 0x00,
ZQ_Motor_Controller, WaitTime); //用户实际速度反馈(0.1rpm)
}
void Position_Immediately_Setting(uint8_t MotorID, FDCANHandler *ZQ_Motor_Controller,int32_t Deri_Position,int32_t Deri_Speed, int32_t WaitTime) // Home 设置当前位置为零点
{
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x607A, 0x00, Deri_Position, ZQ_Motor_Controller, WaitTime); //设置位置
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x6081, 0x00, Deri_Speed, ZQ_Motor_Controller, WaitTime); //设置速度
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2B, 0x6040, 0x00, 0x2f, ZQ_Motor_Controller, WaitTime);
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2B, 0x6040, 0x00, 0x3f, ZQ_Motor_Controller, WaitTime);
}
void Position_Lag_Setting(uint8_t MotorID, FDCANHandler *ZQ_Motor_Controller,int32_t Deri_Position,int32_t Deri_Speed, int32_t WaitTime) // Home 设置当前位置为零点
{
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x607A, 0x00, Deri_Position, ZQ_Motor_Controller, WaitTime); //设置位置
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x23, 0x6081, 0x00, Deri_Speed, ZQ_Motor_Controller, WaitTime); //设置速度
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2B, 0x6040, 0x00, 0x0f, ZQ_Motor_Controller, WaitTime);
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2B, 0x6040, 0x00, 0x1f, ZQ_Motor_Controller, WaitTime);
}
void Position_Lay_Setting(uint8_t MotorID, FDCANHandler *ZQ_Motor_Controller,int32_t Deri_Position,int32_t Deri_Speed, int32_t WaitTime) // Home 设置当前位置为零点
{
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2f, 0x6098, 0x00, 0x23,
ZQ_Motor_Controller, WaitTime); //1. 设置定位的方式,向索引0x6098:00写入0X23
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2f, 0x6060, 0x00, 0x06,
ZQ_Motor_Controller, WaitTime); //2:设置操作模式,向索引0x6060:00写入0x06
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x80,
ZQ_Motor_Controller, WaitTime); //3:清除异常,向控制字0x6040:00写入0x80
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x06,
ZQ_Motor_Controller, WaitTime); //4.伺服准备,向控制字0x6040:00写入0x06
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x07,
ZQ_Motor_Controller, WaitTime); //5. 伺服等待使能,向控制字0x6040:00写入0x07
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2b, 0x6040, 0x00, 0x0f,
ZQ_Motor_Controller, WaitTime); //6. 伺服使能 向控制字 0x6040:00写入0x0F
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x2f, 0x6040, 0x00, 0x1f,
ZQ_Motor_Controller, WaitTime); //7. :启动原点定位,向控制字0x6040:00写入0x1F
CANSendMessageSDO_ADD_To_SendList(MotorID, 0x40, 0x6041, 0x00, 0x0,
ZQ_Motor_Controller, 100); //8. :启动原点定位,向控制字0x6040:00写入0x1F
}
void TT_Request_Velocity(uint32_t Motor_ID_1, FDCANHandler *ZQ_Motor_Controller,
int32_t WaitTime)
{
CANSendMessageSDO_ADD_To_SendList(Motor_ID_1, 0x40, 0x606c, 0x00, 0x00,
ZQ_Motor_Controller, WaitTime); //用户实际速度反馈(0.1rpm)
}
//
//
void TT_Request_Fault(uint32_t Motor_ID_1, FDCANHandler *ZQ_Motor_Controller,
int32_t WaitTime)
{
CANSendMessageSDO_ADD_To_SendList(Motor_ID_1, 0x40, 0x300A, 0x00, 0x00,
ZQ_Motor_Controller, WaitTime);
}
void TT_Request_Current(uint32_t Motor_ID_1, FDCANHandler *ZQ_Motor_Controller,
int32_t WaitTime)
{
CANSendMessageSDO_ADD_To_SendList(Motor_ID_1, 0x40, 0x6078, 0x00, 0x00,
ZQ_Motor_Controller, WaitTime);
}
void TT_Analytic_Fun(int32_t ID_A_T_A, char *buffer)
{
int Function_code = (int) ((int16_t) (buffer[1] | buffer[2] << 8));
switch (Function_code)
{
case 24672:
TT_Motor[ID_A_T_A]->Cont_Posi_Suc = 1;
break;
case 24707:
TT_Motor[ID_A_T_A]->Acc_Suc = 1;
break;
case 24708:
TT_Motor[ID_A_T_A]->Dec_Suc = 1;
break;
case 24698:
TT_Motor[ID_A_T_A]->Target_Posi_Suc = 1;
break;
case 24705:
TT_Motor[ID_A_T_A]->Run_Speed_Suc = 1;
break;
case 24640:
TT_Motor[ID_A_T_A]->Clear_Suc = 1;
break;
case 8220:
TT_Motor[ID_A_T_A]->Acc_Suc_Speed = 1;
break;
case 24831:
TT_Motor[ID_A_T_A]->Suc_Speed_S = 1;
break;
case 8221:
TT_Motor[ID_A_T_A]->Dec_Suc_Speed = 1;
break;
case 24676:
{
TT_Motor[ID_A_T_A]->Real_Position = (int) (buffer[4]
| (buffer[5]) << 8 | (buffer[6]) << 16 | (buffer[7] << 24));
if (TT_Motor[ID_A_T_A]->Start_Measuring == 1)
{
TT_Motor[ID_A_T_A]->Start_Measuring =0;
TT_Motor[ID_A_T_A]->Number_Of_Rounds=0;
TT_Motor[ID_A_T_A]->Start_Measuring_Position=TT_Motor[ID_A_T_A]->Real_Position;
TT_Motor[ID_A_T_A]->Last_Real_Position=TT_Motor[ID_A_T_A]->Real_Position;
}
else
{
if (abs(
TT_Motor[ID_A_T_A]->Real_Position
- TT_Motor[ID_A_T_A]->Last_Real_Position)
>= 30000)
{
if (TT_Motor[ID_A_T_A]->Real_Position > 0)
{
TT_Motor[ID_A_T_A]->Number_Of_Rounds -= 1;
}
else
{
TT_Motor[ID_A_T_A]->Number_Of_Rounds += 1;
}
}
}
TT_Motor[ID_A_T_A]->Last_Real_Position =
TT_Motor[ID_A_T_A]->Real_Position;
double CircleLength = 3.14 * 280/1000 ; //pi*d //m
double _tempDeltCounts = TT_Motor[ID_A_T_A]->Real_Position
- TT_Motor[ID_A_T_A]->Start_Measuring_Position;
TT_Motor[ID_A_T_A]->Real_Disatnce = (_tempDeltCounts/ 32768/101
+ (double) TT_Motor[ID_A_T_A]->Number_Of_Rounds
)
* CircleLength;
}
break;
case 24684:
TT_Motor[ID_A_T_A]->Real_Velcity = (int) (buffer[4]
| (buffer[5]) << 8 | (buffer[6]) << 16 | (buffer[7] << 24));
break;
case 24696:
TT_Motor[ID_A_T_A]->Real_Current = (int) (buffer[4]
| (buffer[5]) << 8 | (buffer[6]) << 16 | (buffer[7] << 24)); //0.1A
break;
case 12298://0x3001
TT_Motor[ID_A_T_A]->TT_Motor_Fault = (int) (buffer[4]
| (buffer[5]) << 8 | (buffer[6]) << 16 | (buffer[7] << 24));
break;
default:
if ((buffer[0] == (0XAA)) | (buffer[1] == (0XBB)))
{
TT_Motor[ID_A_T_A]->Act_Suc = 1;
}
break;
}
}

98
Bingoo/base/msp_WH_LTE_7S0.c

@ -0,0 +1,98 @@
#include "BHBF_ROBOT.h"
#include "bsp_decode_command.h"
#include "gpio.h"
#include "BSP/bsp_UART.h"
#include <msp_WH_LTE_7S0.h>
char NeedToFeedBackToComputer = 0;
struct UARTHandler *wh_LTE_7S0_Handler;
DispacherController* wh_LTE_7S0_dispacher;
void Reset()
{
HAL_GPIO_WritePin(S0_RESET_GPIO_Port, S0_RESET_Pin, GPIO_PIN_RESET);
}
void NormalState()
{
HAL_GPIO_WritePin(S0_RESET_GPIO_Port, S0_RESET_Pin, GPIO_PIN_SET);
}
void WH_LTE_7S0_intialize(struct UARTHandler *Handler)
{
//NormalState();
HAL_GPIO_WritePin(S0_RESET_GPIO_Port, GPIO_PIN_10, GPIO_PIN_SET);
wh_LTE_7S0_Handler = Handler;
wh_LTE_7S0_Handler->Wait_time = 40; // 最低不要低于4;
wh_LTE_7S0_dispacher=Handler->dispacherController;
//不周期性发送
wh_LTE_7S0_dispacher->Dispacher_Enable=1;
wh_LTE_7S0_dispacher->Add_Dispatcher_List(wh_LTE_7S0_dispacher,UpdateGV);
wh_LTE_7S0_dispacher->DispacherCallTime=1000;
//DispacherController* disp=wh_LTE_7S0_Handler->dispacherController;
//disp->Add_Dispatcher_List(disp,UpdateGV);//周期性update GV数据
LOG("WH_LTE_7S0_intialize");
wh_LTE_7S0_Handler->UART_Decode = decode_received_data_from_computer; //indicate that there is no need to listen
}
void Send_WH_LTE_7S0_Data(uint8_t *data, int length)
{
char datass[100];
memcpy(datass, data, length);
wh_LTE_7S0_Handler->UART_Decode = decode_received_data_from_computer;
memcpy(wh_LTE_7S0_Handler->Tx_Buf, data, length);
wh_LTE_7S0_Handler->TxCount = length;
wh_LTE_7S0_Handler->UART_Tx(wh_LTE_7S0_Handler);
}
void UpdateGV()
{
//wh_LTE_7S0_Handler->UART_Decode = decode_received_data_from_computer;
pb_ostream_t GV_o_stream =
{ 0 };
char buf[1024];
GV_o_stream = pb_ostream_from_buffer(buf, sizeof(buf));
pb_encode(&GV_o_stream, GV_struct_define_fields, &GV);
memcpy(&wh_LTE_7S0_Handler->Tx_Buf[2], buf, GV_o_stream.bytes_written);
wh_LTE_7S0_Handler->Tx_Buf[0]='1';
wh_LTE_7S0_Handler->Tx_Buf[1]=',';
//wh_LTE_7S0_Handler->Tx_Buf[2]='1';
wh_LTE_7S0_Handler->TxCount = GV_o_stream.bytes_written+2;
wh_LTE_7S0_Handler->UART_Tx(wh_LTE_7S0_Handler);
}
void decode_received_data_from_computer(uint8_t *buffer, uint16_t length)
{
char buf[1024];
memcpy(buf, buffer, length);
if(buffer[0]=='2'&&buffer[1]==',')
{
//Decode protobuf
//decode_command_from_computer(buffer+2,length-2);
decode_command_and_feedback(buffer+2,length-2,1,wh_LTE_7S0_Handler);
}
if(NeedToFeedBackToComputer==1)
{
send_received_data_to_upper_computer(buffer, length);
}
}

20
Bingoo/base/msp_ZQ_MotorParameters.pb.c

@ -0,0 +1,20 @@
/* Automatically generated nanopb constant definitions */
/* Generated by nanopb-0.4.8 */
#include "msp_ZQ_MotorParameters.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
PB_BIND(TT_MotorParameters, TT_MotorParameters, AUTO)
#ifndef PB_CONVERT_DOUBLE_FLOAT
/* On some platforms (such as AVR), double is really float.
* To be able to encode/decode double on these platforms, you need.
* to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line.
*/
PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES)
#endif

135
Bingoo/base/msp_ground_management.c

@ -0,0 +1,135 @@
/*
* msp_ground_management.c
*
* Created on: 2026115
* Author: xsq
*/
#include "msp_ground_management.h"
#include "msp_strain_gauge.h"
uint8_t ground_management_slave_id = 0x34;
struct UARTHandler *ground_management_handler;
ground_management_struct *ground_management_value;
DispacherController *ground_management_dispacherController;
void decode_ground_management(uint8_t *buffer, uint16_t length);
void ground_management_intialize(struct UARTHandler *Handler)
{
ground_management_handler = Handler;
ground_management_handler->Wait_time = 10; //等待10ms 最低不要低于4;
ground_management_dispacherController = Handler->dispacherController;
ground_management_dispacherController->Dispacher_Enable = 1;
//不周期性发送
ground_management_dispacherController->Add_Dispatcher_List(
ground_management_dispacherController, ground_management_inquiry);
HardWareErrorController->Add_PCOMHardWare(HardWareErrorController,
"ground_management", 0, ComError_Ground_Management);
LOG("battery_intialize");
}
void ground_management_intialize_with_slaveid(struct UARTHandler *Handler,
int slave_id)
{
ground_management_intialize(Handler);
ground_management_slave_id = slave_id;
}
uint16_t dataToSend[10];
uint16_t g_m_read_count= 10;
uint16_t decoded_ground_management_holdingReg_value[20];
void ground_management_inquiry()
{
// void MB_WriteNumHoldingReg(uint8_t *Tx_Buf, uint8_t *TxCount_t, uint8_t _addr,
// uint16_t _reg, uint16_t _num, uint8_t *_databuf)
dataToSend[0] = SWAP_ENDIAN_16((uint16_t ) ground_management_value->K1);
dataToSend[1] = SWAP_ENDIAN_16((uint16_t ) ground_management_value->K2);
dataToSend[2] = SWAP_ENDIAN_16((uint16_t ) ground_management_value->K3);
dataToSend[3] = SWAP_ENDIAN_16((uint16_t ) ground_management_value->K4);
dataToSend[4] = SWAP_ENDIAN_16((uint16_t ) ground_management_value->K5_Default);
dataToSend[5] = SWAP_ENDIAN_16(
(uint16_t ) ground_management_value->MaualControlPower);
dataToSend[6] = SWAP_ENDIAN_16(
(uint16_t ) ground_management_value->MaualPowerState);
ground_management_value->Time_Out_Period=400;
dataToSend[7] = SWAP_ENDIAN_16(
(uint16_t ) ground_management_value->Time_Out_Period);
MB_WriteNumHoldingReg(&ground_management_handler->Tx_Buf,
&ground_management_handler->TxCount, ground_management_slave_id, 0,
8, dataToSend);
ground_management_handler->AddSendList(ground_management_handler,
ground_management_handler->Tx_Buf,
ground_management_handler->TxCount, OneLineWaitTime, NULL);
/***********寄存器8写德玛克电机速度*****************************/
MB_WriteHoldingReg(&ground_management_handler->Tx_Buf,
&ground_management_handler->TxCount, ground_management_slave_id,
8, GV.GroundManagementValue.DMK_Speed);
ground_management_handler->AddSendList(ground_management_handler,
ground_management_handler->Tx_Buf,
ground_management_handler->TxCount, OneLineWaitTime, NULL);
/***********寄存器9写德玛克电机状态*****************************/
MB_WriteHoldingReg(&ground_management_handler->Tx_Buf,
&ground_management_handler->TxCount, ground_management_slave_id,
9, GV.GroundManagementValue.DMK_WorkState);
ground_management_handler->AddSendList(ground_management_handler,
ground_management_handler->Tx_Buf,
ground_management_handler->TxCount, OneLineWaitTime, NULL);
/********************************************************************/
if (ground_management_value->Save_To_Flash == 1)
{
/******************写寄存器7超时时间**************************/
MB_WriteHoldingReg(&ground_management_handler->Tx_Buf,
&ground_management_handler->TxCount, ground_management_slave_id,
7, (uint16_t)ground_management_value->Time_Out_Period);
ground_management_handler->AddSendList(ground_management_handler,
ground_management_handler->Tx_Buf,
ground_management_handler->TxCount, OneLineWaitTime, NULL);
/***************************寄存器10 写入55保存数据*************************************/
MB_WriteHoldingReg(&ground_management_handler->Tx_Buf,
&ground_management_handler->TxCount, ground_management_slave_id,
10, 55);
ground_management_handler->AddSendList(ground_management_handler,
ground_management_handler->Tx_Buf,
ground_management_handler->TxCount, OneLineWaitTime, NULL);
/*****************************************************/
ground_management_value->Save_To_Flash=0;
}
MB_ReadHoldingReg(&ground_management_handler->Tx_Buf, &ground_management_handler->TxCount, ground_management_slave_id, 0,
g_m_read_count);
ground_management_handler->AddSendList(ground_management_handler, ground_management_handler->Tx_Buf,
ground_management_handler->TxCount, OneLineWaitTime, decode_ground_management);
}
void decode_ground_management(uint8_t *buffer, uint16_t length)
{
// uint8_t data1[length];
// memcpy(data1, buffer, length);
int decoded_result = MB_Decode_HoldingRegs(buffer, length, g_m_read_count,
&decoded_ground_management_holdingReg_value[0]);
if (decoded_result == 1)
{
ground_management_value->Read_Time_Out_Period = decoded_ground_management_holdingReg_value[7];
HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,
"ground_management", 1);
// LOG("Battery_sensor succeeded and the force is %d", *CMCU06_ForceValue);
}
else
{
LOGFF(DL_ERROR, "ground_management decoding failed");
}
}

137
Bingoo/base/msp_strain_gauge.c

@ -0,0 +1,137 @@
/*
* msp_strain_gauge.c
*
* Created on: 20251125
* Author: akeguo
*/
#include "msp_strain_gauge.h"
//应变片采集模块
Strain_Gauge_Struct *strainGaugeValue;
uint8_t strain_gauge_slave_id = 0x32; //默认为1
int SAVE_Register9=0; //设置55 保存KD
int SAVE_Register23=0; //设置KD
struct UARTHandler *strain_gauge_handler;
DispacherController *strain_gauge_dispacherController;
void strain_gauge_loop();
void decode_strain_gauge_01(uint8_t *buffer, uint16_t length);
void decode_strain_gauge_09(uint8_t *buffer, uint16_t length);
void strain_gauge_intialize(struct UARTHandler *Handler)
{
//strain_gauge_slave_id=slave_id;
strain_gauge_handler = Handler;
strain_gauge_handler->Wait_time = 10; //等待10ms 最低不要低于4;
strain_gauge_dispacherController = Handler->dispacherController;
strain_gauge_dispacherController->Dispacher_Enable = 1;
//不周期性发送
strain_gauge_dispacherController->Add_Dispatcher_List(
strain_gauge_dispacherController, strain_gauge_loop);//Dispatcher_List_Add_t bsp com helper.c
HardWareErrorController->Add_PCOMHardWare(HardWareErrorController,
"strain_gauge", 0, ComError_Strain_Gauge);
LOG("strain_gauge_intialize");
}
void strain_gauge_intialize_with_slaveid(struct UARTHandler *Handler,
int slave_id)
{
strain_gauge_intialize(Handler);
strain_gauge_slave_id = slave_id;
}
void strain_gauge_loop()
{
// 必须要初始化 strainGaugeValue
//读取力
MB_ReadHoldingReg(&strain_gauge_handler->Tx_Buf,
&strain_gauge_handler->TxCount, strain_gauge_slave_id, 1, 1); //03 command ; read 3 registers 从1 开始 读取1个
strain_gauge_handler->AddSendList(strain_gauge_handler,
strain_gauge_handler->Tx_Buf, strain_gauge_handler->TxCount, OneLineWaitTime,
decode_strain_gauge_01);
//推杆控制
MB_WriteHoldingReg(&strain_gauge_handler->Tx_Buf,
&strain_gauge_handler->TxCount, strain_gauge_slave_id, 0,
strainGaugeValue->MotorControl);//strainGaugeValue->MotorControl 电机控制,=0 停止,=1 前进,=2 后退
strain_gauge_handler->AddSendList(strain_gauge_handler,
strain_gauge_handler->Tx_Buf, strain_gauge_handler->TxCount, OneLineWaitTime,
NULL);
/*写寄存器2 3 KD**/
if(SAVE_Register23==1)
{
/*写寄存器2 K**/
MB_WriteHoldingReg(&strain_gauge_handler->Tx_Buf,
&strain_gauge_handler->TxCount, strain_gauge_slave_id, 2,
strainGaugeValue->HX711_K);
strain_gauge_handler->AddSendList(strain_gauge_handler,
strain_gauge_handler->Tx_Buf, strain_gauge_handler->TxCount, OneLineWaitTime,
NULL);
/*写寄存器3 D**/
MB_WriteHoldingReg(&strain_gauge_handler->Tx_Buf,
&strain_gauge_handler->TxCount, strain_gauge_slave_id, 3,
strainGaugeValue->HX711_D);
strain_gauge_handler->AddSendList(strain_gauge_handler,
strain_gauge_handler->Tx_Buf, strain_gauge_handler->TxCount, OneLineWaitTime,
NULL);
SAVE_Register23=0;
}
/*写寄存器9 设置为55保存KD**/
if(SAVE_Register9==1)
{
MB_WriteHoldingReg(&strain_gauge_handler->Tx_Buf,
&strain_gauge_handler->TxCount, strain_gauge_slave_id, 9,
strainGaugeValue->Save);
strain_gauge_handler->AddSendList(strain_gauge_handler,
strain_gauge_handler->Tx_Buf, strain_gauge_handler->TxCount, OneLineWaitTime,
NULL);
SAVE_Register9=0;
}
}
int16_t decoded_strain_gauge_holdingReg_value[20];
//读取 00-02的寄存器
void decode_strain_gauge_01(uint8_t *buffer, uint16_t length)
{
// uint8_t data1[length];
// memcpy(data1, buffer, length);
int decoded_result = MB_Decode_HoldingRegs(buffer, length, 1,
&decoded_strain_gauge_holdingReg_value[1]);
if (decoded_result == 1)
{
strainGaugeValue->Pressure = decoded_strain_gauge_holdingReg_value[1];
HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,
"strain_gauge", 1);
// LOG("Battery_sensor succeeded and the force is %d", *CMCU06_ForceValue);
}
else
{
LOGFF(DL_ERROR, "strain_gauge_decoding failed");
}
}
//读取 09的寄存器
void decode_strain_gauge_09(uint8_t *buffer, uint16_t length)
{
// uint8_t data1[100];
// memcpy(data1, buffer, length);
int decoded_result = MB_Decode_HoldingRegs(buffer, length, 2,
&decoded_strain_gauge_holdingReg_value[9]);
if (decoded_result == 1)
{
strainGaugeValue->Save = decoded_strain_gauge_holdingReg_value[9];
HardWareErrorController->Set_PCOMHardWare(HardWareErrorController,
"strain_gauge", 1);
// LOG("Battery_sensor succeeded and the force is %d", *CMCU06_ForceValue);
}
else
{
LOGFF(DL_ERROR, "strain_gauge_decoding failed");
}
}

102
Bingoo/base/paint_gun_action.c

@ -0,0 +1,102 @@
/*
* paint_gun_action.c
*
* Created on: 202587
* Author: xsq
*/
#include "paint_gun_action.h"
#include "Handset_Status_Setting.h"
#include "msp_strain_gauge.h"
#include "fsm_state.h"
#include "BHBF_ROBOT.h"
transition_t current_paintgun_state; /*transition_t 成员是 指针的 transition_state_t */
transition_state_t paintgun_on_state={PaintGun_ON_Enter,PaintGun_ON_Do,NULL}; /* State 成员,它会被默认初始化为 0 */
transition_state_t paintgun_off_state={PaintGun_OFF_Enter,PaintGun_OFF_Do,NULL};
char Paint_Gun_ButtonReset_Flag = 0; //喷枪开启 1yes
/* 喷枪控制 */
void PaintGun_ON_Do()
{
GF_BSP_GPIO_SetIO(PaintGun_IO_CTL, K_ON_PaintGun);//0开
}
void PaintGun_OFF_Do()
{
GF_BSP_GPIO_SetIO(PaintGun_IO_CTL, K_OFF_PaintGun);//1关
}
void PaintGun_ON_Enter()
{
}
void PaintGun_ON_Exit()
{
}
void PaintGun_OFF_Enter()
{
}
void PaintGun_OFF_Exit()
{
}
IO_State curr_io_state;
//无压力传感器数值下控制推杆函数
void PaintGun_Contronl()
{
GV.Now_press=strainGaugeValue->Pressure;
curr_io_state = GetIOState();
if(curr_io_state==IO_STATE_RISE)
{
strainGaugeValue->MotorControl=1;
}
else if(curr_io_state==IO_STATE_DESCEND)
{
strainGaugeValue->MotorControl=2;
}
else
{
strainGaugeValue->MotorControl=0;
}
}
//有压力传感器数值下控制推杆函数
void PaintGun_Contronl_Press()
{
GV.Now_press=strainGaugeValue->Pressure;
curr_io_state = GetIOState();
if(curr_io_state==IO_STATE_RISE)
{
// if(strainGaugeValue->Pressure>(-GV.PV.Robot_Press_Set))
// {
// strainGaugeValue->MotorControl=1;
// }
strainGaugeValue->MotorControl=1;
}
else if(curr_io_state==IO_STATE_DESCEND)
{
if(strainGaugeValue->Pressure<=(GV.PV.Robot_Press_Set*10))
{
strainGaugeValue->MotorControl=2;
}
else
{
strainGaugeValue->MotorControl=0;
}
}
else
{
strainGaugeValue->MotorControl=0;
}
}

388
Bingoo/base/pb_common.c

@ -0,0 +1,388 @@
/* pb_common.c: Common support functions for pb_encode.c and pb_decode.c.
*
* 2014 Petteri Aimonen <jpa@kapsi.fi>
*/
#include "pb_common.h"
static bool load_descriptor_values(pb_field_iter_t *iter)
{
uint32_t word0;
uint32_t data_offset;
int_least8_t size_offset;
if (iter->index >= iter->descriptor->field_count)
return false;
word0 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index]);
iter->type = (pb_type_t)((word0 >> 8) & 0xFF);
switch(word0 & 3)
{
case 0: {
/* 1-word format */
iter->array_size = 1;
iter->tag = (pb_size_t)((word0 >> 2) & 0x3F);
size_offset = (int_least8_t)((word0 >> 24) & 0x0F);
data_offset = (word0 >> 16) & 0xFF;
iter->data_size = (pb_size_t)((word0 >> 28) & 0x0F);
break;
}
case 1: {
/* 2-word format */
uint32_t word1 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 1]);
iter->array_size = (pb_size_t)((word0 >> 16) & 0x0FFF);
iter->tag = (pb_size_t)(((word0 >> 2) & 0x3F) | ((word1 >> 28) << 6));
size_offset = (int_least8_t)((word0 >> 28) & 0x0F);
data_offset = word1 & 0xFFFF;
iter->data_size = (pb_size_t)((word1 >> 16) & 0x0FFF);
break;
}
case 2: {
/* 4-word format */
uint32_t word1 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 1]);
uint32_t word2 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 2]);
uint32_t word3 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 3]);
iter->array_size = (pb_size_t)(word0 >> 16);
iter->tag = (pb_size_t)(((word0 >> 2) & 0x3F) | ((word1 >> 8) << 6));
size_offset = (int_least8_t)(word1 & 0xFF);
data_offset = word2;
iter->data_size = (pb_size_t)word3;
break;
}
default: {
/* 8-word format */
uint32_t word1 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 1]);
uint32_t word2 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 2]);
uint32_t word3 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 3]);
uint32_t word4 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 4]);
iter->array_size = (pb_size_t)word4;
iter->tag = (pb_size_t)(((word0 >> 2) & 0x3F) | ((word1 >> 8) << 6));
size_offset = (int_least8_t)(word1 & 0xFF);
data_offset = word2;
iter->data_size = (pb_size_t)word3;
break;
}
}
if (!iter->message)
{
/* Avoid doing arithmetic on null pointers, it is undefined */
iter->pField = NULL;
iter->pSize = NULL;
}
else
{
iter->pField = (char*)iter->message + data_offset;
if (size_offset)
{
iter->pSize = (char*)iter->pField - size_offset;
}
else if (PB_HTYPE(iter->type) == PB_HTYPE_REPEATED &&
(PB_ATYPE(iter->type) == PB_ATYPE_STATIC ||
PB_ATYPE(iter->type) == PB_ATYPE_POINTER))
{
/* Fixed count array */
iter->pSize = &iter->array_size;
}
else
{
iter->pSize = NULL;
}
if (PB_ATYPE(iter->type) == PB_ATYPE_POINTER && iter->pField != NULL)
{
iter->pData = *(void**)iter->pField;
}
else
{
iter->pData = iter->pField;
}
}
if (PB_LTYPE_IS_SUBMSG(iter->type))
{
iter->submsg_desc = iter->descriptor->submsg_info[iter->submessage_index];
}
else
{
iter->submsg_desc = NULL;
}
return true;
}
static void advance_iterator(pb_field_iter_t *iter)
{
iter->index++;
if (iter->index >= iter->descriptor->field_count)
{
/* Restart */
iter->index = 0;
iter->field_info_index = 0;
iter->submessage_index = 0;
iter->required_field_index = 0;
}
else
{
/* Increment indexes based on previous field type.
* All field info formats have the following fields:
* - lowest 2 bits tell the amount of words in the descriptor (2^n words)
* - bits 2..7 give the lowest bits of tag number.
* - bits 8..15 give the field type.
*/
uint32_t prev_descriptor = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index]);
pb_type_t prev_type = (prev_descriptor >> 8) & 0xFF;
pb_size_t descriptor_len = (pb_size_t)(1 << (prev_descriptor & 3));
/* Add to fields.
* The cast to pb_size_t is needed to avoid -Wconversion warning.
* Because the data is is constants from generator, there is no danger of overflow.
*/
iter->field_info_index = (pb_size_t)(iter->field_info_index + descriptor_len);
iter->required_field_index = (pb_size_t)(iter->required_field_index + (PB_HTYPE(prev_type) == PB_HTYPE_REQUIRED));
iter->submessage_index = (pb_size_t)(iter->submessage_index + PB_LTYPE_IS_SUBMSG(prev_type));
}
}
bool pb_field_iter_begin(pb_field_iter_t *iter, const pb_msgdesc_t *desc, void *message)
{
memset(iter, 0, sizeof(*iter));
iter->descriptor = desc;
iter->message = message;
return load_descriptor_values(iter);
}
bool pb_field_iter_begin_extension(pb_field_iter_t *iter, pb_extension_t *extension)
{
const pb_msgdesc_t *msg = (const pb_msgdesc_t*)extension->type->arg;
bool status;
uint32_t word0 = PB_PROGMEM_READU32(msg->field_info[0]);
if (PB_ATYPE(word0 >> 8) == PB_ATYPE_POINTER)
{
/* For pointer extensions, the pointer is stored directly
* in the extension structure. This avoids having an extra
* indirection. */
status = pb_field_iter_begin(iter, msg, &extension->dest);
}
else
{
status = pb_field_iter_begin(iter, msg, extension->dest);
}
iter->pSize = &extension->found;
return status;
}
bool pb_field_iter_next(pb_field_iter_t *iter)
{
advance_iterator(iter);
(void)load_descriptor_values(iter);
return iter->index != 0;
}
bool pb_field_iter_find(pb_field_iter_t *iter, uint32_t tag)
{
if (iter->tag == tag)
{
return true; /* Nothing to do, correct field already. */
}
else if (tag > iter->descriptor->largest_tag)
{
return false;
}
else
{
pb_size_t start = iter->index;
uint32_t fieldinfo;
if (tag < iter->tag)
{
/* Fields are in tag number order, so we know that tag is between
* 0 and our start position. Setting index to end forces
* advance_iterator() call below to restart from beginning. */
iter->index = iter->descriptor->field_count;
}
do
{
/* Advance iterator but don't load values yet */
advance_iterator(iter);
/* Do fast check for tag number match */
fieldinfo = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index]);
if (((fieldinfo >> 2) & 0x3F) == (tag & 0x3F))
{
/* Good candidate, check further */
(void)load_descriptor_values(iter);
if (iter->tag == tag &&
PB_LTYPE(iter->type) != PB_LTYPE_EXTENSION)
{
/* Found it */
return true;
}
}
} while (iter->index != start);
/* Searched all the way back to start, and found nothing. */
(void)load_descriptor_values(iter);
return false;
}
}
bool pb_field_iter_find_extension(pb_field_iter_t *iter)
{
if (PB_LTYPE(iter->type) == PB_LTYPE_EXTENSION)
{
return true;
}
else
{
pb_size_t start = iter->index;
uint32_t fieldinfo;
do
{
/* Advance iterator but don't load values yet */
advance_iterator(iter);
/* Do fast check for field type */
fieldinfo = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index]);
if (PB_LTYPE((fieldinfo >> 8) & 0xFF) == PB_LTYPE_EXTENSION)
{
return load_descriptor_values(iter);
}
} while (iter->index != start);
/* Searched all the way back to start, and found nothing. */
(void)load_descriptor_values(iter);
return false;
}
}
static void *pb_const_cast(const void *p)
{
/* Note: this casts away const, in order to use the common field iterator
* logic for both encoding and decoding. The cast is done using union
* to avoid spurious compiler warnings. */
union {
void *p1;
const void *p2;
} t;
t.p2 = p;
return t.p1;
}
bool pb_field_iter_begin_const(pb_field_iter_t *iter, const pb_msgdesc_t *desc, const void *message)
{
return pb_field_iter_begin(iter, desc, pb_const_cast(message));
}
bool pb_field_iter_begin_extension_const(pb_field_iter_t *iter, const pb_extension_t *extension)
{
return pb_field_iter_begin_extension(iter, (pb_extension_t*)pb_const_cast(extension));
}
bool pb_default_field_callback(pb_istream_t *istream, pb_ostream_t *ostream, const pb_field_t *field)
{
if (field->data_size == sizeof(pb_callback_t))
{
pb_callback_t *pCallback = (pb_callback_t*)field->pData;
if (pCallback != NULL)
{
if (istream != NULL && pCallback->funcs.decode != NULL)
{
return pCallback->funcs.decode(istream, field, &pCallback->arg);
}
if (ostream != NULL && pCallback->funcs.encode != NULL)
{
return pCallback->funcs.encode(ostream, field, &pCallback->arg);
}
}
}
return true; /* Success, but didn't do anything */
}
#ifdef PB_VALIDATE_UTF8
/* This function checks whether a string is valid UTF-8 text.
*
* Algorithm is adapted from https://www.cl.cam.ac.uk/~mgk25/ucs/utf8_check.c
* Original copyright: Markus Kuhn <http://www.cl.cam.ac.uk/~mgk25/> 2005-03-30
* Licensed under "Short code license", which allows use under MIT license or
* any compatible with it.
*/
bool pb_validate_utf8(const char *str)
{
const pb_byte_t *s = (const pb_byte_t*)str;
while (*s)
{
if (*s < 0x80)
{
/* 0xxxxxxx */
s++;
}
else if ((s[0] & 0xe0) == 0xc0)
{
/* 110XXXXx 10xxxxxx */
if ((s[1] & 0xc0) != 0x80 ||
(s[0] & 0xfe) == 0xc0) /* overlong? */
return false;
else
s += 2;
}
else if ((s[0] & 0xf0) == 0xe0)
{
/* 1110XXXX 10Xxxxxx 10xxxxxx */
if ((s[1] & 0xc0) != 0x80 ||
(s[2] & 0xc0) != 0x80 ||
(s[0] == 0xe0 && (s[1] & 0xe0) == 0x80) || /* overlong? */
(s[0] == 0xed && (s[1] & 0xe0) == 0xa0) || /* surrogate? */
(s[0] == 0xef && s[1] == 0xbf &&
(s[2] & 0xfe) == 0xbe)) /* U+FFFE or U+FFFF? */
return false;
else
s += 3;
}
else if ((s[0] & 0xf8) == 0xf0)
{
/* 11110XXX 10XXxxxx 10xxxxxx 10xxxxxx */
if ((s[1] & 0xc0) != 0x80 ||
(s[2] & 0xc0) != 0x80 ||
(s[3] & 0xc0) != 0x80 ||
(s[0] == 0xf0 && (s[1] & 0xf0) == 0x80) || /* overlong? */
(s[0] == 0xf4 && s[1] > 0x8f) || s[0] > 0xf4) /* > U+10FFFF? */
return false;
else
s += 4;
}
else
{
return false;
}
}
return true;
}
#endif

1727
Bingoo/base/pb_decode.c

File diff suppressed because it is too large

1000
Bingoo/base/pb_encode.c

File diff suppressed because it is too large

1074
Bingoo/base/robot_move_actions.c

File diff suppressed because it is too large

100
Bingoo/base/swing_action.c

@ -0,0 +1,100 @@
/*
* swing_action.c
*
* Created on: Mar 4, 2026
* Author: 42961
*/
#include "swing_action.h"
#include "Handset_Status_Setting.h"
#include "fsm_state.h"
#include "BHBF_ROBOT.h"
#define TT_One_Deg_Count 11014///32768*121/360(减速比121)=11014
#define LEFT_LIMIT 1
#define RIGHT_LIMIT 2
float Swing_Speed_Deg_Sencond=201.7;//HJ32-121
int middle_position=-944334;
//int center_angle;
//int offset_angle;
//int center_position; //中间位置-944334
int limit_record=0;
float left_compare_value=0;
float right_compare_value=0;
float left_compare_updata;
float right_compare_updata;
int lef_positon=-569580;
int Right_positon=-1230420;
//手动摆臂函数
void Robot_Swing_Operation_Function()
{
if(P_MK32->CH0_RY_H>500)
{
GV.SwingMotor.Position_immediately1_Lag2=1;
GV.Tar_Position_angle=90;
GV.Tar_Position_Velcity_Degree_S=GV.Robot_Swing_Speed;
}
else if(P_MK32->CH0_RY_H<-500)
{
GV.SwingMotor.Position_immediately1_Lag2=1;
GV.Tar_Position_angle=-90;
GV.Tar_Position_Velcity_Degree_S=GV.Robot_Swing_Speed;
}
else
{
Move_Swing_Halt_Func_Do();
}
}
//摆臂电机左转延时生效
void Move_Swing_Left_Func_Do_lay(void)
{
GV.SwingMotor.Position_immediately1_Lag2=2;
GV.Tar_Position_angle=left_compare_value;
GV.Tar_Position_Velcity_Degree_S=GV.Robot_Swing_Speed;
}
//摆臂电机右转延时生效
void Move_Swing_Right_Func_Do_lay(void)
{
GV.SwingMotor.Position_immediately1_Lag2=2;
GV.Tar_Position_angle=right_compare_value;
GV.Tar_Position_Velcity_Degree_S=GV.Robot_Swing_Speed;
}
//摆臂电机左转立即执行
void Move_Swing_Left_Func_Do_imm(void)
{
GV.SwingMotor.Position_immediately1_Lag2=1;
GV.Tar_Position_angle=left_compare_value;
GV.Tar_Position_Velcity_Degree_S=GV.Robot_Swing_Speed;
}
//摆臂电机右转立即执行
void Move_Swing_Right_Func_Do_imm(void)
{
GV.SwingMotor.Position_immediately1_Lag2=1;
GV.Tar_Position_angle=right_compare_value;
GV.Tar_Position_Velcity_Degree_S=GV.Robot_Swing_Speed;
}
void Move_Swing_Halt_Func_Do(void)
{
GV.SwingMotor.Position_immediately1_Lag2=1;
GV.SwingMotor.Tar_Position_count=0;
GV.Tar_Position_Velcity_Degree_S=0;
}

251
Bingoo/base/tcp_server.c

@ -0,0 +1,251 @@
#include "tcp_server.h"
#include "lwip/tcp.h"
#include "lwip/memp.h"
#include <string.h>
#include "lwip.h"
#include "string.h"
#include "bsp_UDP.h"
#include "bsp_DLT_Log.h"
#include <bsp_UpperComputer_Handler.h>
#include "BSP/bsp_GPIO.h"
static client_conn_t clients[MAX_CLIENTS];
static struct tcp_pcb *server_pcb = NULL;
void send_tcp(SendDataNode **head);
// 回调函数声明
static err_t tcp_accept_cb(void *arg, struct tcp_pcb *newpcb, err_t err);
static err_t tcp_recv_cb(void *arg, struct tcp_pcb *tpcb, struct pbuf *p,
err_t err);
static void tcp_err_cb(void *arg, err_t err);
static void tcp_sent_cb(void *arg, struct tcp_pcb *tpcb, u16_t len);
SendDataNode *pTcpHead = NULL; /*初始化链表头指针,使其为空*/
void tcp_server_timer_callback();
char listIndex = 0;
SendDataNode* CreateSendDataNode(uint8_t *tx_Buf, uint8_t tx_count)
{
SendDataNode *newNode = (SendDataNode*) malloc(sizeof(SendDataNode));
if (newNode == NULL)
{
return NULL;
}
memcpy(newNode->Tx_Buf, tx_Buf, tx_count);
newNode->Tx_Count = tx_count;
newNode->next = NULL;
return newNode;
}
void insertAtTail(SendDataNode **head, uint8_t *tx_Buf, uint8_t tx_count)
{
SendDataNode *newNode = CreateSendDataNode(tx_Buf, tx_count);
// 如果链表为空
if (*head == NULL)
{
*head = newNode;
return;
}
listIndex = 0;
// 遍历到链表尾部
SendDataNode *current = *head;
while (current->next != NULL)
{
// listIndex++;
// if (listIndex >= 50)
// {
// free(current);
// return;
// }
current = current->next;
}
//SendDataNode *newNode = CreateSendDataNode(tx_Buf, tx_count);
current->next = newNode; // 尾部节点指向新节点
}
void tcp_add_sendList(uint8_t *tx_Buf, uint8_t tx_count)
{
for (int i = 0; i < MAX_CLIENTS; i++)
{
if (clients[i].active)
{
insertAtTail(&pTcpHead, tx_Buf, tx_count);
return;
}
}
}
void send_tcp(SendDataNode **head)
{
if (*head == NULL)
{
return;
}
tcp_send_to_all_clients((*head)->Tx_Buf, (*head)->Tx_Count);
SendDataNode *temp = *head;
*head = (*head)->next;
free(temp);
}
// 初始化TCP服务器
void tcp_server_init(uint16_t port)
{
GF_BSP_Interrupt_Add_CallBack(
DF_BSP_InterCall_TIM8_2ms_PeriodElapsedCallback,
tcp_server_timer_callback);
err_t err;
// 创建TCP控制块
server_pcb = tcp_new_ip_type(IPADDR_TYPE_ANY);
if (!server_pcb) return;
// 绑定到指定端口
err = tcp_bind(server_pcb, IP_ANY_TYPE, port);
if (err != ERR_OK)
{
memp_free(MEMP_TCP_PCB, server_pcb);
server_pcb = NULL;
return;
}
// 开始监听
server_pcb = tcp_listen(server_pcb);
if (!server_pcb) return;
// 设置接受连接回调
tcp_accept(server_pcb, tcp_accept_cb);
// 初始化客户端数组
memset(clients, 0, sizeof(clients));
}
// 接受新连接回调
static err_t tcp_accept_cb(void *arg, struct tcp_pcb *newpcb, err_t err)
{
LWIP_UNUSED_ARG(arg);
LWIP_UNUSED_ARG(err);
// 查找空闲的客户端槽位
int free_index = -1;
for (int i = 0; i < MAX_CLIENTS; i++)
{
if (!clients[i].active)
{
free_index = i;
break;
}
}
if (free_index == -1)
{
// 没有可用槽位,拒绝连接
tcp_abort(newpcb);
return ERR_ABRT;
}
// 配置新连接
tcp_setprio(newpcb, TCP_PRIO_MIN);
tcp_recv(newpcb, tcp_recv_cb);
tcp_err(newpcb, tcp_err_cb);
tcp_sent(newpcb, tcp_sent_cb);
// 保存客户端信息
clients[free_index].pcb = newpcb;
clients[free_index].active = 1;
return ERR_OK;
}
// 接收数据回调
static err_t tcp_recv_cb(void *arg, struct tcp_pcb *tpcb, struct pbuf *p,
err_t err)
{
LWIP_UNUSED_ARG(arg);
if (!p)
{
// 连接关闭
for (int i = 0; i < MAX_CLIENTS; i++)
{
if (clients[i].pcb == tpcb)
{
clients[i].active = 0;
break;
}
}
tcp_close(tpcb);
return ERR_OK;
}
// 处理接收到的数据(这里简单释放)
tcp_recved(tpcb, p->tot_len);
pbuf_free(p);
return ERR_OK;
}
// 错误回调
static void tcp_err_cb(void *arg, err_t err)
{
LWIP_UNUSED_ARG(err);
for (int i = 0; i < MAX_CLIENTS; i++)
{
if (clients[i].pcb == arg)
{
clients[i].active = 0;
break;
}
}
}
// 数据发送完成回调
static void tcp_sent_cb(void *arg, struct tcp_pcb *tpcb, u16_t len)
{
LWIP_UNUSED_ARG(arg);
LWIP_UNUSED_ARG(tpcb);
LWIP_UNUSED_ARG(len);
// 可在此实现流量控制
}
// 向所有活跃客户端发送数据
void tcp_send_to_all_clients(const char *data, uint16_t len)
{
for (int i = 0; i < MAX_CLIENTS; i++)
{
if (clients[i].active)
{
//clients[i].pcb->flags=
// err_t err = tcp_write(clients[i].pcb, data, len,
// TCP_WRITE_FLAG_COPY);
err_t err = tcp_write(clients[i].pcb, data, len,
TCP_WRITE_FLAG_COPY);
if (err == ERR_OK)
{
tcp_output(clients[i].pcb);
}
else
{
// 发送失败,关闭连接
//clients[i].active = 0;
//tcp_close(clients[i].pcb);
}
}
}
}
int32_t counter = 0;
// 定时器回调(从主定时器中断调用)
void tcp_server_timer_callback()
{
counter++;
if (counter > 5)
{
counter = 0;
send_tcp(&pTcpHead);
};
}

125
Bingoo/include/base/BHBF_ROBOT.h

@ -0,0 +1,125 @@
/*
* BHBF_ROBOT.h
*
* Created on: Oct 26, 2023
* Author: shiya
*/
#ifndef INC_BHBF_ROBOT_H_
#define INC_BHBF_ROBOT_H_
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <assert.h>
#include <motors.h>
#include <stdbool.h>
#include "BHBF_ROBOT.h"
#include "bsp_PV.pb.h"
#include "bsp_IV.pb.h"
#include "BSP/bsp_TCPClient.h"
#include "BSP/pb.h"
#include "BSP/pb_decode.h"
#include "BSP/pb_encode.h"
#include "BSP/bsp_EEPROM.h"
#include "BSP/bsp_pb_decode_encode.h"
#include "bsp_MB_host.h"
#include "BSP/bsp_include.h"
#include "BSP/bsp_UART.h"
#include "BSP/DLTuc.h"
#include "BSP/bsp_DLT_Log.h"
#include "BSP/bsp_cpu_flash.h"
#include "BSP/bsp_qspi_w25q128.h"
#include "BSP/bsp_UpperComputer_Handler.h"
#include "BSP/bsp_Error_Detect.h"
#include "BSP/bsp_MB_host.h"
#include "MSP/msp_JTBATTERY.h"
#include "MSP/msp_Force_Sensor.h"
#include "MSP/msp_TL720D.h"
#include "MSP/msp_MK32_1.h"
#include "MSP/msp_Force_Sensor.h"
#include "MSP/msp_WH_LTE_7S0.h"
#include "paint_gun_action.h"
#include "fsm_state_control.h"
#include "change_line_control.h"
#include "fsm_state.h"
#include "robot_move_actions.h"
//#include "robot_state.h"
//FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 896K
//#define VECT_TAB_OFFSET 0x00020000U
#define DLTViewer 1
extern bool CompareTimer_Delay(int32_t Delay);
extern GV_struct_define GV;
extern IV_struct_define IV;
extern CV_struct_define CV;
extern PV_struct_define decoded_PV;
extern PV_struct_define decoded_PV_variable;
typedef struct sys_timer_handler
{
int start_timer;
int sys_current_timer_count;
int sys_timer_flag;
}Sys_timer_handler;
extern Sys_timer_handler timer_handler_1;
extern Sys_timer_handler timer_handler_2;
extern Sys_timer_handler timer_handler_3;
extern Sys_timer_handler timer_handler_4;
//first start Timer, then WaitTimer
extern bool CompareTimer(int32_t DelayMiliSeconds,Sys_timer_handler * timer_handler);
extern void SystemTimer_Intialize();
extern void GF_Timer_Count();
extern void GF_Robot_Init(void);
extern void GF_Robot_MainLoop(void);
extern void GF_WatchDog_Loop(void);
extern int32_t speed_M_min_toE01_M_min(int32_t speedm_min);
extern void SET_BIT_1(int32_t* num,int32_t k);
extern void SET_BIT_0(int32_t* num,int32_t k);
extern int32_t Get_BIT(int32_t* num,int32_t k);
//A &= ~(1 << bit)
extern int32_t* SystemErrorCode;
extern ErrorData* SystemErrorData;
#define IV_Run_Mode_Maunal 0
#define IV_Run_Mode_Automation 1
#define IV_Run_Mode_EmergencyStop 2
#define IV_Run_Mode_Vertical_LaneChange 3
#define IV_Run_Mode_Horizontal_LaneChange 4
#define IV_Run_Mode_Forward 5
#define IV_Run_Mode_BackWard 6
#define IV_Run_Mode_TurnLeft 7
#define IV_Run_Mode_TurnRight 8
#define IV_Run_Mode_HALT 9
//extern LS_MotorParameters* Frames_Motor[4];
extern int32_t SystemTimeMiliCount; //2ms加一
#endif /* INC_BHBF_ROBOT_H_ */

248
Bingoo/include/base/DLTuc.h

@ -0,0 +1,248 @@
/**
* @file DLTuc.h
* @author teodor
* @date 1 Jul 2022
* @brief This file is a part of DLTuc library
*
* In this header, you can find types, Api functions, which are provided by DLTuc library
* Usefull macros, for convience usage of DLTuc library in logging purposes
*
* Requirments:
* Around ~2kB of RAM
* Check Configuration file and defines:
* DLT_TRANSMIT_RING_BUFFER_SIZE, DLT_TRANSMIT_MAX_SINGLE_MESSAGE_SIZE
*
*/
#ifndef INC_DLT_LOGS_MCU_H_
#define INC_DLT_LOGS_MCU_H_
/*
* *******************************************************************************************
* Includes
* *******************************************************************************************
* */
#include "stdint.h"
#include <stdarg.h>
#include <string.h>
#include "DLTucConfig.h"
/*
* *******************************************************************************************
* Exported defines
* *******************************************************************************************
* */
/*@brief
*
* - convert the To strings to uint32_t
*/
#define DLT_LOG_ECUID_VALUE ((uint32_t)((((uint32_t) ((uint8_t)DLT_LOG_ECUID[0])) << 24UL) | \
(((uint32_t) ((uint8_t)DLT_LOG_ECUID[1])) << 16UL) | \
(((uint32_t) ((uint8_t)DLT_LOG_ECUID[2])) << 8UL) | \
((uint32_t)((uint8_t)DLT_LOG_ECUID[3]))))
#define DLT_LOG_APPID_VALUE ((uint32_t)((((uint32_t) ((uint8_t)DLT_LOG_APPID[0])) << 24UL) | \
(((uint32_t) ((uint8_t)DLT_LOG_APPID[1])) << 16UL) | \
(((uint32_t) ((uint8_t)DLT_LOG_APPID[2])) << 8UL) | \
((uint32_t)((uint8_t)DLT_LOG_APPID[3]))))
#define DLT_LOG_CONTEX_VALUE ((uint32_t)((((uint32_t) ((uint8_t)DLT_LOG_CONTEX[0])) << 24UL) | \
(((uint32_t) ((uint8_t)DLT_LOG_CONTEX[1])) << 16UL) | \
(((uint32_t) ((uint8_t)DLT_LOG_CONTEX[2])) << 8UL) | \
((uint32_t)((uint8_t)DLT_LOG_CONTEX[3]))))
/*
* Definitions of DLT services.
*/
#define DLT_SERVICE_ID_SET_LOG_LEVEL 0x01 /**< Service ID: Set log level */
#define DLT_SERVICE_ID_SETRACE_STATUS 0x02 /**< Service ID: Set trace status */
#define DLT_SERVICE_ID_GET_LOG_INFO 0x03 /**< Service ID: Get log info */
#define DLT_SERVICE_ID_GET_DEFAULT_LOG_LEVEL 0x04 /**< Service ID: Get dafault log level */
#define DLT_SERVICE_ID_STORE_CONFIG 0x05 /**< Service ID: Store configuration */
#define DLT_SERVICE_ID_RESETO_FACTORY_DEFAULT 0x06 /**< Service ID: Reset to factory defaults */
#define DLT_SERVICE_ID_SET_COM_INTERFACE_STATUS 0x07 /**< Service ID: Set communication interface status */
#define DLT_SERVICE_ID_SET_COM_INTERFACE_MAX_BANDWIDTH 0x08 /**< Service ID: Set communication interface maximum bandwidth */
#define DLT_SERVICE_ID_SET_VERBOSE_MODE 0x09 /**< Service ID: Set verbose mode */
#define DLT_SERVICE_ID_SET_MESSAGE_FILTERING 0x0A /**< Service ID: Set message filtering */
#define DLT_SERVICE_ID_SETIMING_PACKETS 0x0B /**< Service ID: Set timing packets */
#define DLT_SERVICE_ID_GET_LOCALIME 0x0C /**< Service ID: Get local time */
#define DLT_SERVICE_ID_USE_ECU_ID 0x0D /**< Service ID: Use ECU id */
#define DLT_SERVICE_ID_USE_SESSION_ID 0x0E /**< Service ID: Use session id */
#define DLT_SERVICE_ID_USEIMESTAMP 0x0F /**< Service ID: Use timestamp */
#define DLT_SERVICE_ID_USE_EXTENDED_HEADER 0x10 /**< Service ID: Use extended header */
#define DLT_SERVICE_ID_SET_DEFAULT_LOG_LEVEL 0x11 /**< Service ID: Set default log level */
#define DLT_SERVICE_ID_SET_DEFAULTRACE_STATUS 0x12 /**< Service ID: Set default trace status */
#define DLT_SERVICE_ID_GET_SOFTWARE_VERSION 0x13 /**< Service ID: Get software version */
#define DLT_SERVICE_ID_MESSAGE_BUFFER_OVERFLOW 0x14 /**< Service ID: Message buffer overflow */
#define DLT_SERVICE_ID_CALLSW_CINJECTION 0xFFF /**< Service ID: Message Injection (minimal ID) */
/*
* *******************************************************************************************
* Exported types
* *******************************************************************************************
* */
/**!
* \brief DltLogLevel_t
* \details Typdef used to identify the DLT log level
* */
typedef enum
{
DL_FATAL =1,
DL_ERROR =2,
DL_WARN =3,
DL_INFO =4,
DL_DEBUG =5,
DL_VERBOSE =6,
}DltLogLevel_t;
/*
* *******************************************************************************************
* Exported function - API
* *******************************************************************************************
* */
/*!
************************************************************************************************
* \brief DLTuc_RawDataReceiveDone
* \details OPTIONAL - Use only if you need handle data receive, like Injection messages
* Call the function to inform DLTuc that Raw data packet has been received
************************************************************************************************/
void DLTuc_RawDataReceiveDone(uint16_t Size);
/*!
************************************************************************************************
* \brief DLTuc_RegisterReceiveSerialDataFunction
* \details OPTIONAL - Use only if you need handle data receive, like Injection messages.
* - Register callback function which will be used by DLTuc to start data receive process.
* The Callback function is basicly called only after registration and if data packet has been received,
* to start again receive data packet
* \param in LLSerialRecDataFunctionC ...
************************************************************************************************/
void DLTuc_RegisterReceiveSerialDataFunction(void LLSerialRecDataFunctionC(uint8_t *DltLogData, uint16_t Size));
/*!
************************************************************************************************
* \brief DLTuc_RegisterInjectionDataReceivedCb
* \details OPTIONAL - Use only if you need handle data receive, like Injection messages
* Register injection data received call back
* Use the function if you want register call back function to handle the Injection messages in your application
* \param in InjectionDataRcvd ...
************************************************************************************************/
void DLTuc_RegisterInjectionDataReceivedCb
(void InjectionDataRcvd(uint32_t AppId, uint32_t ConId,uint32_t ServId,uint8_t *Data, uint16_t Size));
/*!
************************************************************************************************
* \brief DLTuc_RegisterTransmitSerialDataFunction
* \details This simple stack/library must be initialized by "DLTuc_RegisterTransmitSerialDataFunction"
* As a parameter must be passed function which will transmit serial data
* \param in LLSerialTrDataFunctionC transmit function pointer
************************************************************************************************/
void DLTuc_RegisterTransmitSerialDataFunction(void LLSerialTrDataFunctionC(uint8_t *DltLogData, uint8_t Size));
/*!
************************************************************************************************
* \brief DLTuc_RegisterGetTimeStampMsCallback
* \details function to update time stamp in library
* \param in GetSysTime - pointer to function which allow to read system time in msec
*************************************************************************************************/
void DLTuc_RegisterGetTimeStampMsCallback(uint32_t GetSysTime(void));
/*!
************************************************************************************************
* \brief DLTuc_MessageTransmitDone
* \details IMPORTANT!!!!!
* Call this function when the transsmision is end
* For example in "DMA transmission end callback" to inform the lib that the message is transmitted
************************************************************************************************
* */
void DLTuc_MessageTransmitDone(void);
/*!
************************************************************************************************
* \brief DLTuc_LogOutVarArgs
* \details default function to create DLT Log
* \param DltLogLevel_t Level - of Dlt log
* \param in AppId - size of the "DltLogData" (return value)
* \param in ContextId - pointer to the message stored in RingBuffer (return value)
* \param in Payload String to send as dlt log
* \param in ... parameters same as in printf function
*************************************************************************************************/
void DLTuc_LogOutVarArgs(DltLogLevel_t Level, uint32_t AppId, uint32_t ContextId, uint8_t *Payload, ...);
/*
* *******************************************************************************************
* Additional macros to facilitate the use of the library
* *******************************************************************************************
* */
#ifdef LOGS_ENABLE
/**!
* \brief LOGL(level, str, ...)
* \details Transmit DltLog using function DLTuc_LogOutVarArgs but user don't have to add
* log_level, DLT_LOG_APPID_VALUE and DLT_LOG_CONTEX_VALUE
*
* */
#define LOG(str, ...)\
if(DL_INFO <= DLT_LOG_ENABLE_LEVEL){\
DLTuc_LogOutVarArgs(DL_INFO, DLT_LOG_APPID_VALUE, DLT_LOG_CONTEX_VALUE,(uint8_t *) str, ##__VA_ARGS__);\
}
/**!
* \brief LOGL(level, str, ...)
* \details Transmit DltLog using function DLTuc_LogOutVarArgs but user don't have to add DLT_LOG_APPID_VALUE and DLT_LOG_CONTEX_VALUE
*
* */
#define LOGL(log_level, str, ...)\
if(log_level <= DLT_LOG_ENABLE_LEVEL){\
DLTuc_LogOutVarArgs(log_level, DLT_LOG_APPID_VALUE, DLT_LOG_CONTEX_VALUE,(uint8_t *) str, ##__VA_ARGS__);\
}
/**!
* @brief LOGF(log_level, str, ...)
* \details Transmit DltLog using function DLTuc_LogOutVarArgs but user don't have to add DLT_LOG_APPID_VALUE and DLT_LOG_CONTEX_VALUE
* Additionally add the name of the calling function
*
*
* */
#define LOGF(log_level, str, ...)\
if(log_level <= DLT_LOG_ENABLE_LEVEL){\
DLTuc_LogOutVarArgs(log_level, DLT_LOG_APPID_VALUE, DLT_LOG_CONTEX_VALUE,(uint8_t *) "FUN:%s LOG: "str, __FUNCTION__,##__VA_ARGS__);\
}
/**!
* \brief LOGFF(log_level, str, ...)
* \details Transmit DltLog using function DLTuc_LogOutVarArgs but user don't have to add DLT_LOG_APPID_VALUE and DLT_LOG_CONTEX_VALUE
* Additionally add the name of the calling function and file name
*
*
* */
#define LOGFF(log_level, str, ...)\
if(log_level <= DLT_LOG_ENABLE_LEVEL){\
DLTuc_LogOutVarArgs(log_level, DLT_LOG_APPID_VALUE, DLT_LOG_CONTEX_VALUE,(uint8_t *)"FILE:%s LINE: %d FUN:%s LOG: "str,__FILE__,__LINE__,__FUNCTION__,##__VA_ARGS__);\
}
#else
LOG(str, ...)
LOGL(log_level, str, ...)
LOGF(log_level, str, ...)
LOGFF(log_level, str, ...)
#endif
#endif /* INC_DLT_LOGS_MCU_H_ */

74
Bingoo/include/base/DLTucConfig.h

@ -0,0 +1,74 @@
/**
* @file DLTuc.c
* @author teodor
* @date 1 Jul 2022
* @brief This file is a part of DLTuc library
*
* In this header file is placed DLTuc configuration template
*
*/
#if 1 /*Set it to "1" to enable content*/
#ifndef __DLT_CONFIG__
/*Comment this line to turn off all logs..*/
#define LOGS_ENABLE
/*Pass here the entry critical entry function for your RTOS or
Interrupt block functions if you want use the library from diffrent context*/
#define DLTuc_OS_CRITICAL_START()
#define DLTuc_OS_CRITICAL_END()
/*Default minimum log level to transmit the log*/
//#ifndef DLT_LOG_ENABLE_LEVEL
////#define DLT_LOG_ENABLE_LEVEL DL_VERBOSE
// #define DLT_LOG_ENABLE_LEVEL 0
//#endif
extern char DLT_LOG_ENABLE_LEVEL;
/**!
* \brief DLT_LOG_CONTEX
* \details to define the minimum level log which will printed using the debug macros
*
*/
#ifndef DLT_LOG_CONTEX
#define DLT_LOG_CONTEX "DFLT"
#endif
/**!
* \brief DLT_LOG_APPID
* \details to define the minimum level log which will printed using the debug macros
*
*/
#ifndef DLT_LOG_APPID
#define DLT_LOG_APPID "0000"
#endif
/**!
* \brief DLT_LOG_ECUID
* \details you can define here you ECUID ..
*
*/
#define DLT_LOG_ECUID "uCID" /*Electronic Controller Unit ID*/
#define DLT_ECU_SW_VER 0001
/*
*@brief DLT_TRANSMIT_MAX_SINGLE_MESSAGE_SIZE & DLT_TRANSMIT_RING_BUFFER_SIZE
* these values define the size of the circular buffer and the maximum size of a single DLT message
* Size of out Circular DLT messages buffer is equal: DLT_TRANSMIT_MAX_SINGLE_MESSAGE_SIZE*DLT_TRANSMIT_RING_BUFFER_SIZE
*/
#define DLT_TRANSMIT_MAX_SINGLE_MESSAGE_SIZE 255
#define DLT_TRANSMIT_RING_BUFFER_SIZE 15
#define DLT_REC_SINGLE_MESSAGE_MAX_SIZE 255
#define DLT_RECEIVE_RING_BUFFER_SIZE 2
#endif //__DLT_CONFIG__
#endif //Content enable

73
Bingoo/include/base/Handset_Status_Setting.h

@ -0,0 +1,73 @@
/*
* Handset_Status_Setting.h
*
* Created on: 2026115
* Author: bm673
*/
#ifndef FSM_INC_HANDSET_STATUS_SETTING_H_
#define FSM_INC_HANDSET_STATUS_SETTING_H_
// 按键定义
typedef enum {
EMERGENCE_STOP=0, // SE和SF同时按下触发急停
INPUT_NONE , // 无输入
// 摇杆方向
INPUT_ROCKER_STOP, // 摇杆停止
INPUT_ROCKER_FORWARD, // 摇杆前进
INPUT_ROCKER_BACKWARD, // 摇杆后退
INPUT_ROCKER_TURN_LEFT, // 摇杆左转
INPUT_ROCKER_TURN_RIGHT, // 摇杆右转
// 按键
INPUT_KEY_LANE_CHANGE_UP, // CH4_SA = -1000 换道上
INPUT_KEY_LANE_CHANGE_DOWN, // CH4_SA = 1000 换道下
INPUT_KEY_FORWARD_CRUISE, // CH5_SB = -1000 前进巡航
INPUT_KEY_BACKWARD_CRUISE, // CH5_SB = 1000 后退巡航
INPUT_KEY_AUTO_WORK_UP, // CH7_SD = -1000 自动作业上
INPUT_KEY_AUTO_WORK_DOWN, // CH7_SD = 1000 自动作业下
INPUT_KEY_AUTO_WELD, // CH6_SC = -1000 焊缝跟踪
//摆臂
INPUT_ROCKER_SWING, //动摆臂了
KEY_COUNT, // 输入总数
} InputEvent;
// 主状态枚举,串口状态定义
typedef enum {
Serial_Mode_Config,
Action_Execute,
Action_Shut_down,
MAIN_STATE_COUNT
} MainState;
// 机器人模式枚举
typedef enum {
Halt_Mode = 0,
Manual_Mode,
Horizontal_Mode,
Flat_Mode,
Vertical_Mode_Left,
Vertical_Mode_Right,
Regional_Horizontal_Automatic_Task,
Regional_Flat_Automatic_Task,
MODE_COUNT // 模式总数
} Robot_Mode;
// IO状态枚举
typedef enum {
IO_STATE_NONE,
IO_STATE_RISE,
IO_STATE_DESCEND
} IO_State;
// 函数声明
Robot_Mode RobotRockerState(void);
InputEvent RemoteControl_GetKeyIndex(Robot_Mode current_mode);
void PV_control(void);
void IV_control(void);
IO_State GetIOState(void);
#endif /* FSM_INC_HANDSET_STATUS_SETTING_H_ */

125
Bingoo/include/base/bsp_CV.pb.h

@ -0,0 +1,125 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_CV_PB_H_INCLUDED
#define PB_BSP_CV_PB_H_INCLUDED
#include "pb.h"
#include "bsp_PV.pb.h"
#include "bsp_PID.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
typedef struct _CV_struct_define {
int32_t Speed_m_per_min; /* MPMin = 1m/min 1米每分钟 m/min */
int32_t LeftTurnSpeed;
int32_t RightTurnSpeed;
int32_t RobotLeftAngleValue; /* 水平左方向 单位0.01° */
int32_t RobotRightAngleValue; /* 水平右方向角度值 单位0.01° */
int32_t RobotUpAngleValue; /* 竖直方向角度值 单位0.01° */
int32_t RobotDownAngleValue; /* 竖直向下角度值 单位0.01° */
int32_t Robot_Permitted_Angler_Error_Value_E_2D; /* 作业时需用的最大角度偏差值 0.01°,超出将停止作业 */
int32_t Robot_Angle_Start_BaseE_2D; /* 角度值 0.01° */
int32_t Lane_Change_Speed_m_per_min;
int32_t Is_Automation_Authorized;
int32_t Is_Function_Authorized;
int32_t Joy_Sticker_Angle_Allowance; /* 例如在90度的±30° */
int32_t Joy_Sticker_Value_Allowance; /* 例如 joysticker的值超过600 */
int32_t Allowable_Error_For_Angle_Tracking; /* 纠偏角度跟踪的允许误差1 度 */
int32_t Paint_Gun_Shutdown_Distance; /* 喷枪关闭距离,喷枪关闭后多上厘米停止运行 */
int32_t Horizontal_ChangeLane_Compensation; /* 水平换道补偿距离 */
int32_t Vertical_ChangeLane_Compensation; /* 竖直换道补偿距离 */
int32_t pulse_Per_Circle; /* 每转多少脉冲 */
int32_t wheel_Reduction_Ratio; /* 减速比 */
double wheel_Diameter_m; /* 车轮直径 m */
bool has_PID_high;
PID_Parameters PID_high;
bool has_PID_mid;
PID_Parameters PID_mid;
bool has_PID_low;
PID_Parameters PID_low;
} CV_struct_define;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define CV_struct_define_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, false, PID_Parameters_init_default, false, PID_Parameters_init_default, false, PID_Parameters_init_default}
#define CV_struct_define_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, false, PID_Parameters_init_zero, false, PID_Parameters_init_zero, false, PID_Parameters_init_zero}
/* Field tags (for use in manual encoding/decoding) */
#define CV_struct_define_Speed_m_per_min_tag 1
#define CV_struct_define_LeftTurnSpeed_tag 2
#define CV_struct_define_RightTurnSpeed_tag 3
#define CV_struct_define_RobotLeftAngleValue_tag 4
#define CV_struct_define_RobotRightAngleValue_tag 5
#define CV_struct_define_RobotUpAngleValue_tag 6
#define CV_struct_define_RobotDownAngleValue_tag 7
#define CV_struct_define_Robot_Permitted_Angler_Error_Value_E_2D_tag 8
#define CV_struct_define_Robot_Angle_Start_BaseE_2D_tag 9
#define CV_struct_define_Lane_Change_Speed_m_per_min_tag 10
#define CV_struct_define_Is_Automation_Authorized_tag 11
#define CV_struct_define_Is_Function_Authorized_tag 12
#define CV_struct_define_Joy_Sticker_Angle_Allowance_tag 13
#define CV_struct_define_Joy_Sticker_Value_Allowance_tag 14
#define CV_struct_define_Allowable_Error_For_Angle_Tracking_tag 15
#define CV_struct_define_Paint_Gun_Shutdown_Distance_tag 16
#define CV_struct_define_Horizontal_ChangeLane_Compensation_tag 17
#define CV_struct_define_Vertical_ChangeLane_Compensation_tag 18
#define CV_struct_define_pulse_Per_Circle_tag 19
#define CV_struct_define_wheel_Reduction_Ratio_tag 20
#define CV_struct_define_wheel_Diameter_m_tag 21
#define CV_struct_define_PID_high_tag 22
#define CV_struct_define_PID_mid_tag 23
#define CV_struct_define_PID_low_tag 24
/* Struct field encoding specification for nanopb */
#define CV_struct_define_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, Speed_m_per_min, 1) \
X(a, STATIC, SINGULAR, INT32, LeftTurnSpeed, 2) \
X(a, STATIC, SINGULAR, INT32, RightTurnSpeed, 3) \
X(a, STATIC, SINGULAR, INT32, RobotLeftAngleValue, 4) \
X(a, STATIC, SINGULAR, INT32, RobotRightAngleValue, 5) \
X(a, STATIC, SINGULAR, INT32, RobotUpAngleValue, 6) \
X(a, STATIC, SINGULAR, INT32, RobotDownAngleValue, 7) \
X(a, STATIC, SINGULAR, INT32, Robot_Permitted_Angler_Error_Value_E_2D, 8) \
X(a, STATIC, SINGULAR, INT32, Robot_Angle_Start_BaseE_2D, 9) \
X(a, STATIC, SINGULAR, INT32, Lane_Change_Speed_m_per_min, 10) \
X(a, STATIC, SINGULAR, INT32, Is_Automation_Authorized, 11) \
X(a, STATIC, SINGULAR, INT32, Is_Function_Authorized, 12) \
X(a, STATIC, SINGULAR, INT32, Joy_Sticker_Angle_Allowance, 13) \
X(a, STATIC, SINGULAR, INT32, Joy_Sticker_Value_Allowance, 14) \
X(a, STATIC, SINGULAR, INT32, Allowable_Error_For_Angle_Tracking, 15) \
X(a, STATIC, SINGULAR, INT32, Paint_Gun_Shutdown_Distance, 16) \
X(a, STATIC, SINGULAR, INT32, Horizontal_ChangeLane_Compensation, 17) \
X(a, STATIC, SINGULAR, INT32, Vertical_ChangeLane_Compensation, 18) \
X(a, STATIC, SINGULAR, INT32, pulse_Per_Circle, 19) \
X(a, STATIC, SINGULAR, INT32, wheel_Reduction_Ratio, 20) \
X(a, STATIC, SINGULAR, DOUBLE, wheel_Diameter_m, 21) \
X(a, STATIC, OPTIONAL, MESSAGE, PID_high, 22) \
X(a, STATIC, OPTIONAL, MESSAGE, PID_mid, 23) \
X(a, STATIC, OPTIONAL, MESSAGE, PID_low, 24)
#define CV_struct_define_CALLBACK NULL
#define CV_struct_define_DEFAULT NULL
#define CV_struct_define_PID_high_MSGTYPE PID_Parameters
#define CV_struct_define_PID_mid_MSGTYPE PID_Parameters
#define CV_struct_define_PID_low_MSGTYPE PID_Parameters
extern const pb_msgdesc_t CV_struct_define_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define CV_struct_define_fields &CV_struct_define_msg
/* Maximum encoded size of messages (where known) */
#define BSP_CV_PB_H_MAX_SIZE CV_struct_define_size
#define CV_struct_define_size 358
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

80
Bingoo/include/base/bsp_Cmd.pb.h

@ -0,0 +1,80 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_CMD_PB_H_INCLUDED
#define PB_BSP_CMD_PB_H_INCLUDED
#include "pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
/* this message is used for the computer to send command */
typedef struct _Cmd {
int32_t CommadNum;
/* 定义 1 上位机获取默认CV值
2 CV值
3 CV值
4 Trace等级值
5
6 0
7
8
9 Parameter0 Parameter0
Buff_Data_Length */
int32_t Parameter0;
int32_t Parameter1;
int32_t Parameter2;
int32_t Parameter3;
int32_t Parameter4;
int32_t Buff_Data_Length;
pb_byte_t Buff_Data[512];
} Cmd;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define Cmd_init_default {0, 0, 0, 0, 0, 0, 0, {0}}
#define Cmd_init_zero {0, 0, 0, 0, 0, 0, 0, {0}}
/* Field tags (for use in manual encoding/decoding) */
#define Cmd_CommadNum_tag 1
#define Cmd_Parameter0_tag 2
#define Cmd_Parameter1_tag 3
#define Cmd_Parameter2_tag 4
#define Cmd_Parameter3_tag 5
#define Cmd_Parameter4_tag 6
#define Cmd_Buff_Data_Length_tag 7
#define Cmd_Buff_Data_tag 8
/* Struct field encoding specification for nanopb */
#define Cmd_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, CommadNum, 1) \
X(a, STATIC, SINGULAR, INT32, Parameter0, 2) \
X(a, STATIC, SINGULAR, INT32, Parameter1, 3) \
X(a, STATIC, SINGULAR, INT32, Parameter2, 4) \
X(a, STATIC, SINGULAR, INT32, Parameter3, 5) \
X(a, STATIC, SINGULAR, INT32, Parameter4, 6) \
X(a, STATIC, SINGULAR, INT32, Buff_Data_Length, 7) \
X(a, STATIC, SINGULAR, FIXED_LENGTH_BYTES, Buff_Data, 8)
#define Cmd_CALLBACK NULL
#define Cmd_DEFAULT NULL
extern const pb_msgdesc_t Cmd_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define Cmd_fields &Cmd_msg
/* Maximum encoded size of messages (where known) */
#define BSP_CMD_PB_H_MAX_SIZE Cmd_size
#define Cmd_size 592
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

16
Bingoo/include/base/bsp_DLT_Log.h

@ -0,0 +1,16 @@
/*
* bsp_DLT_Log.h
*
* Created on: Aug 8, 2024
* Author: akeguo
*/
#ifndef INC_BSP_BSP_DLT_LOG_H_
#define INC_BSP_BSP_DLT_LOG_H_
#include "BHBF_ROBOT.h"
extern void dLT_Log_intialize(struct UARTHandler *Handler);
extern void dLT_Log_intialize_udp_tcp();
#endif /* INC_BSP_BSP_DLT_LOG_H_ */

73
Bingoo/include/base/bsp_EEPROM.h

@ -0,0 +1,73 @@
/*
* bsp_EEPROM.h
*
* Created on: Oct 26, 2023
* Author: shiya
*/
#ifndef INC_BSP_EEPROM_H_
#define INC_BSP_EEPROM_H_
#include "bsp_include.h"
#include "bsp_CV.pb.h"
#include "bsp_IAP.pb.h"
#define EEPROM_WP_Pin GPIO_PIN_11
#define EEPROM_WP_GPIO_Port GPIOE
#define EEPROM_SCL_Pin GPIO_PIN_12
#define EEPROM_SCL_GPIO_Port GPIOE
#define EEPROM_SDA_Pin GPIO_PIN_13
#define EEPROM_SDA_GPIO_Port GPIOE
#define AT24C512
#ifdef AT24C512
#define EE_MODEL_NAME "AT24C512"
#define EE_DEV_ADDR 0xA0 /* 设备地址 */
#define EE_PAGE_SIZE 128 /* 页面大小(字节) */
#define EE_SIZE (512*128) /* 总容量(字节) */ // not used in this progrm
#define EE_ADDR_BYTES 2 /* 地址字节个数 */
#endif
#define I2C_WR 0 /* 写控制bit */
#define I2C_RD 1 /* 读控制bit */
//////////////////////////////////////////////////////////////////
//there are 12M eeprom in total, and the code download Address is App_Download_EEPROM_Addr
//512 Pages x 128 Bytes = 65536 Bytes = 512 kbits
#define GF_BSP_EEPROM_CV_struct_define_Start_Address 0
#define IAP_struct_define_Start_Address 512
extern uint16_t App_Download_EEPROM_Addr;
//返回值::1-正常;0-错误
uint8_t GF_BSP_EEPROM_Init(void);
uint8_t GF_BSP_EEPROM_CheckOK(void);
uint8_t GF_BSP_EEPROM_ReadBytes(uint8_t *_pReadBuf, uint16_t _usAddress,
uint16_t _usSize);
uint8_t GF_BSP_EEPROM_WriteBytes(uint8_t *_pWriteBuf, uint16_t _usAddress,
uint16_t _usSize);
CV_struct_define GF_BSP_EEPROM_Get_CV(void);
uint8_t GF_BSP_EEPROM_Set_CV(CV_struct_define cv);
IAP_struct_define GF_BSP_EEPROM_Get_IAP(void);
uint8_t GF_BSP_EEPROM_Set_IAP(IAP_struct_define iap);
PV_struct_define GF_BSP_EEPROM_Get_PV(void);
uint8_t GF_BSP_EEPROM_Set_PV(PV_struct_define pv);
#endif /* INC_BSP_EEPROM_H_ */

78
Bingoo/include/base/bsp_Error.pb.h

@ -0,0 +1,78 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_ERROR_PB_H_INCLUDED
#define PB_BSP_ERROR_PB_H_INCLUDED
#include "pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Enum definitions */
typedef enum _ComError {
ComError_Mk32_SBus = 0, /* proto3版本中,首成员必须为0,成员不应有相同的值 */
ComError_MK32_Serial = 1,
ComError_MK32_InitialState = 2,
ComError_TL720D = 3,
ComError_ZQ_CAN_ID1_LeftMotor = 4,
ComError_ZQ_CAN_ID2_RightMotor = 5,
ComError_ZQ_CAN_ID3_SwingMotor = 6,
ComError_Force_Sensor = 7,
ComError_Mfog40 = 8,
ComError_Ultrasonic_Sensor = 9,
ComError_UWB_20_Error = 10,
ComError_Strain_Gauge = 11,
ComError_Ground_Management = 12
} ComError;
/* Struct definitions */
typedef struct _ErrorData {
int32_t Com_Error_Code;
int32_t Left_Motor_Error_Code;
int32_t Right_Motor_Error_Code;
} ErrorData;
#ifdef __cplusplus
extern "C" {
#endif
/* Helper constants for enums */
#define _ComError_MIN ComError_Mk32_SBus
#define _ComError_MAX ComError_Ground_Management
#define _ComError_ARRAYSIZE ((ComError)(ComError_Ground_Management+1))
/* Initializer values for message structs */
#define ErrorData_init_default {0, 0, 0}
#define ErrorData_init_zero {0, 0, 0}
/* Field tags (for use in manual encoding/decoding) */
#define ErrorData_Com_Error_Code_tag 1
#define ErrorData_Left_Motor_Error_Code_tag 2
#define ErrorData_Right_Motor_Error_Code_tag 3
/* Struct field encoding specification for nanopb */
#define ErrorData_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, Com_Error_Code, 1) \
X(a, STATIC, SINGULAR, INT32, Left_Motor_Error_Code, 2) \
X(a, STATIC, SINGULAR, INT32, Right_Motor_Error_Code, 3)
#define ErrorData_CALLBACK NULL
#define ErrorData_DEFAULT NULL
extern const pb_msgdesc_t ErrorData_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define ErrorData_fields &ErrorData_msg
/* Maximum encoded size of messages (where known) */
#define BSP_ERROR_PB_H_MAX_SIZE ErrorData_size
#define ErrorData_size 33
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

25
Bingoo/include/base/bsp_Error_Detect.h

@ -0,0 +1,25 @@
/*
* bsp_Error_Detect.h
*
* Created on: Oct 23, 2024
* Author: akeguo
*/
#ifndef INC_BSP_BSP_ERROR_DETECT_H_
#define INC_BSP_BSP_ERROR_DETECT_H_
/* Includes ------------------------------------------------------------------*/
#include "BHBF_ROBOT.h"
#include "bsp_com_helper.h"
#include "BSP/bsp_include.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
extern HardWareController *HardWareErrorController;
/* Exported functions ------------------------------------------------------- */
extern char Error_Detect_Enable;
extern void Error_Detect_Intialzie(uint16_t DispacherPeriod);
#endif /* INC_BSP_BSP_ERROR_DETECT_H_ */

84
Bingoo/include/base/bsp_FDCAN.h

@ -0,0 +1,84 @@
/*
* bsp_FDCAN.h
*
* Created on: Oct 26, 2023
* Author: shiya
*/
#ifndef INC_BSP_FDCAN_H_
#define INC_BSP_FDCAN_H_
#include "bsp_Error.pb.h"
#include "bsp_com_helper.h"
uint8_t GF_BSP_FDCAN_Init(void);
void GF_BSP_FDCAN_Senddata(uint8_t FDCAN_CH, uint32_t FrameID,
uint8_t DataLength, uint8_t *Txdata);
extern uint8_t CAN_Buf[8];
extern uint8_t CAN_Buf[8];
extern uint8_t CAN_Buf_2[8];
typedef struct _CANSendHandler
{
uint32_t CAN_ID;
uint32_t SendListTimePeriod;
uint8_t SendLength;
uint8_t Tx_Buf[8];
void (*CAN_Decode)(uint32_t, uint8_t*, uint32_t);
struct _CANSendHandler *pNext;
} CANSendHandler;
typedef struct _FDCANHandler
{
FDCAN_HandleTypeDef *canfd; //CAN to use
struct _DispacherController *dispacherController;
uint8_t timeSpan;
uint8_t SendListExists;
uint32_t SendList_Period; //时间ms
uint32_t SendList_time_Count;
CANSendHandler *pCurrentCANSendHadler; //
void (*AddCANSendList)(struct _FDCANHandler*, uint32_t, uint8_t, uint8_t*,uint32_t,//这里是修改等待时间
void (*CAN_Decode)(uint32_t, uint8_t*, uint32_t));
//void CANHandlerAddTxList(FDCANHandler *handler, uint32_t CAN_ID,uint8_t SendLength, uint8_t *Tx_Buf,uint32_t sendListTimePeriod,void (*CAN_Decode)(uint32_t, uint8_t*, uint32_t)) //参数其实就是一组can数据 在FDHandler添加东西
void (*CAN_Decode)(uint32_t, uint8_t*, uint32_t); // decode can frame, received from other devices
void (*CAN_Send)(struct _FDCANHandler*, uint32_t, uint8_t, uint8_t*);
void (*CAN_Send_Data)(struct _FDCANHandler*);
//(uint8_t FDCAN_CH, uint32_t FrameID,uint8_t DataLength, uint8_t *Txdata)
uint8_t Rx_Buf[128]; //接收缓冲
uint8_t Tx_Buf[128]; //发送缓冲
uint32_t ReceivedLength;//接收长度
uint32_t SendLength; //发送长度
uint32_t ReceivedFrameID; //接收帧ID
uint32_t SendFrameID; //发送帧ID
} FDCANHandler;
extern FDCANHandler FD_CAN_1_Handler;
extern FDCANHandler FD_CAN_2_Handler;
void GF_BSP_CAN_Timer();
void CAN_Send_t(struct _FDCANHandler *fd, uint32_t FrameID, uint8_t DataLength,
uint8_t *Txdata);
void CAN_Send_Data_t(struct _FDCANHandler *fd);
void GF_CAN_Send_List_Send(FDCANHandler *handler);
void CANHandlerAddTxList(FDCANHandler *handler, uint32_t CAN_ID,
uint8_t SendLength, uint8_t *Tx_Buf,uint32_t sendListTimePeriod,
void (*CAN_Decode)(uint32_t, uint8_t*, uint32_t));
void GF_BSP_CANHandler_Init(int can1_sendListPeriod, int can1_DispacherPeriod,
int can2_sendListPeriod, int can2_DispacherPeriod);
void GF_BSP_CANHandler_Init_CAN(FDCANHandler *handler,
FDCAN_HandleTypeDef *canfd, int sendListPeriod, int DispacherPeriod);
void DecodeMotorCAN(uint32_t canID, uint8_t *buffer, uint32_t length);
extern FDCANHandler FD_CAN_1_Handler;
extern FDCANHandler FD_CAN_2_Handler;
extern int32_t CAN_ID;
extern int32_t CAN_ID_2;
#endif /* INC_BSP_FDCAN_H_ */

18
Bingoo/include/base/bsp_GPIO.h

@ -0,0 +1,18 @@
/*
* bsp_GPIO.h
*
* Created on: Oct 26, 2023
* Author: shiya
*/
#ifndef INC_BSP_GPIO_H_
#define INC_BSP_GPIO_H_
#include "bsp_include.h"
uint8_t GF_BSP_GPIO_Init(void);
void GF_BSP_GPIO_SetIO(uint8_t IO_Index,uint8_t Level);
uint8_t GF_BSP_GPIO_ReadIO(uint8_t IO_Index);
uint8_t GF_BSP_GPIO_ToggleIO(uint8_t IO_Index);
#endif /* INC_BSP_GPIO_H_ */

167
Bingoo/include/base/bsp_GV.pb.h

@ -0,0 +1,167 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_GV_PB_H_INCLUDED
#define PB_BSP_GV_PB_H_INCLUDED
#include "pb.h"
#include "msp_MK32.pb.h"
#include "msp_Motor.pb.h"
#include "msp_ZQ_MotorParameters.pb.h"
#include "msp_TL720D.pb.h"
#include "bsp_Error.pb.h"
#include "bsp_PV.pb.h"
#include "bsp_IO.pb.h"
#include "bsp_strain_gauge.pb.h"
#include "bsp_ground_management.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
typedef struct _GV_struct_define {
int32_t TempatureE_2C; /* E_2C=0.01 Celsius 0.01摄氏度 */
float Left_Compensation; /* E_2D =0.01 Degree 0.01度 */
float Right_Compensation; /* 0.01度 */
float Robot_Angle_Desire; /* 机器人期望角度 //改为 float,单位:度(不再需要0.01缩放) */
float Robot_Move_Speed; /* 0.1rpm */
float Robot_Desired_Speed; /* 0.1rpm */
float Left_Speed_M_min; /* m/Min */
float Right_Speed_M_min; /* m/Min */
float Vertical_Adjust; /* 0.1° */
int32_t ForceValue;
int32_t LaneChangeDistance;
bool has_P_MK32;
SP_MSP_MK32_Button P_MK32;
bool has_LeftMotor;
TT_MotorParameters LeftMotor; /* 左电机 ID2 */
bool has_RightMotor;
TT_MotorParameters RightMotor; /* 右电机 ID3 */
bool has_SwingMotor;
TT_MotorParameters SwingMotor; /* 右电机 ID3 */
bool has_TL720DParameters;
MSP_TL720DParameters TL720DParameters;
bool has_IO;
IO_Data IO;
bool has_SystemErrorData;
ErrorData SystemErrorData;
bool has_PV;
PV_struct_define PV; /* 用户配置数据 */
float Tar_Position_angle; /* 位置环模式,期望角度 */
int32_t Tar_Position_Velcity_Degree_S; /* 位置环模式,速度(m/min) */
int32_t symmetricalOrNot;
int32_t Robot_backMode;
int32_t Robot_Swing_Speed;
bool has_Strain_Gauge;
Strain_Gauge_Struct Strain_Gauge;
float weld_data_X;
int32_t weld_exist;
int32_t Now_press;
int32_t turn_center_difference;
bool has_GroundManagementValue;
ground_management_struct GroundManagementValue;
int32_t robot_back_distance;
} GV_struct_define;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define GV_struct_define_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, false, SP_MSP_MK32_Button_init_default, false, TT_MotorParameters_init_default, false, TT_MotorParameters_init_default, false, TT_MotorParameters_init_default, false, MSP_TL720DParameters_init_default, false, IO_Data_init_default, false, ErrorData_init_default, false, PV_struct_define_init_default, 0, 0, 0, 0, 0, false, Strain_Gauge_Struct_init_default, 0, 0, 0, 0, false, ground_management_struct_init_default, 0}
#define GV_struct_define_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, false, SP_MSP_MK32_Button_init_zero, false, TT_MotorParameters_init_zero, false, TT_MotorParameters_init_zero, false, TT_MotorParameters_init_zero, false, MSP_TL720DParameters_init_zero, false, IO_Data_init_zero, false, ErrorData_init_zero, false, PV_struct_define_init_zero, 0, 0, 0, 0, 0, false, Strain_Gauge_Struct_init_zero, 0, 0, 0, 0, false, ground_management_struct_init_zero, 0}
/* Field tags (for use in manual encoding/decoding) */
#define GV_struct_define_TempatureE_2C_tag 1
#define GV_struct_define_Left_Compensation_tag 2
#define GV_struct_define_Right_Compensation_tag 3
#define GV_struct_define_Robot_Angle_Desire_tag 4
#define GV_struct_define_Robot_Move_Speed_tag 5
#define GV_struct_define_Robot_Desired_Speed_tag 6
#define GV_struct_define_Left_Speed_M_min_tag 7
#define GV_struct_define_Right_Speed_M_min_tag 8
#define GV_struct_define_Vertical_Adjust_tag 9
#define GV_struct_define_ForceValue_tag 10
#define GV_struct_define_LaneChangeDistance_tag 11
#define GV_struct_define_P_MK32_tag 12
#define GV_struct_define_LeftMotor_tag 13
#define GV_struct_define_RightMotor_tag 14
#define GV_struct_define_SwingMotor_tag 15
#define GV_struct_define_TL720DParameters_tag 16
#define GV_struct_define_IO_tag 17
#define GV_struct_define_SystemErrorData_tag 18
#define GV_struct_define_PV_tag 19
#define GV_struct_define_Tar_Position_angle_tag 20
#define GV_struct_define_Tar_Position_Velcity_Degree_S_tag 21
#define GV_struct_define_symmetricalOrNot_tag 22
#define GV_struct_define_Robot_backMode_tag 23
#define GV_struct_define_Robot_Swing_Speed_tag 24
#define GV_struct_define_Strain_Gauge_tag 25
#define GV_struct_define_weld_data_X_tag 26
#define GV_struct_define_weld_exist_tag 27
#define GV_struct_define_Now_press_tag 28
#define GV_struct_define_turn_center_difference_tag 29
#define GV_struct_define_GroundManagementValue_tag 30
#define GV_struct_define_robot_back_distance_tag 31
/* Struct field encoding specification for nanopb */
#define GV_struct_define_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, TempatureE_2C, 1) \
X(a, STATIC, SINGULAR, FLOAT, Left_Compensation, 2) \
X(a, STATIC, SINGULAR, FLOAT, Right_Compensation, 3) \
X(a, STATIC, SINGULAR, FLOAT, Robot_Angle_Desire, 4) \
X(a, STATIC, SINGULAR, FLOAT, Robot_Move_Speed, 5) \
X(a, STATIC, SINGULAR, FLOAT, Robot_Desired_Speed, 6) \
X(a, STATIC, SINGULAR, FLOAT, Left_Speed_M_min, 7) \
X(a, STATIC, SINGULAR, FLOAT, Right_Speed_M_min, 8) \
X(a, STATIC, SINGULAR, FLOAT, Vertical_Adjust, 9) \
X(a, STATIC, SINGULAR, INT32, ForceValue, 10) \
X(a, STATIC, SINGULAR, INT32, LaneChangeDistance, 11) \
X(a, STATIC, OPTIONAL, MESSAGE, P_MK32, 12) \
X(a, STATIC, OPTIONAL, MESSAGE, LeftMotor, 13) \
X(a, STATIC, OPTIONAL, MESSAGE, RightMotor, 14) \
X(a, STATIC, OPTIONAL, MESSAGE, SwingMotor, 15) \
X(a, STATIC, OPTIONAL, MESSAGE, TL720DParameters, 16) \
X(a, STATIC, OPTIONAL, MESSAGE, IO, 17) \
X(a, STATIC, OPTIONAL, MESSAGE, SystemErrorData, 18) \
X(a, STATIC, OPTIONAL, MESSAGE, PV, 19) \
X(a, STATIC, SINGULAR, FLOAT, Tar_Position_angle, 20) \
X(a, STATIC, SINGULAR, INT32, Tar_Position_Velcity_Degree_S, 21) \
X(a, STATIC, SINGULAR, INT32, symmetricalOrNot, 22) \
X(a, STATIC, SINGULAR, INT32, Robot_backMode, 23) \
X(a, STATIC, SINGULAR, INT32, Robot_Swing_Speed, 24) \
X(a, STATIC, OPTIONAL, MESSAGE, Strain_Gauge, 25) \
X(a, STATIC, SINGULAR, FLOAT, weld_data_X, 26) \
X(a, STATIC, SINGULAR, INT32, weld_exist, 27) \
X(a, STATIC, SINGULAR, INT32, Now_press, 28) \
X(a, STATIC, SINGULAR, INT32, turn_center_difference, 29) \
X(a, STATIC, OPTIONAL, MESSAGE, GroundManagementValue, 30) \
X(a, STATIC, SINGULAR, INT32, robot_back_distance, 31)
#define GV_struct_define_CALLBACK NULL
#define GV_struct_define_DEFAULT NULL
#define GV_struct_define_P_MK32_MSGTYPE SP_MSP_MK32_Button
#define GV_struct_define_LeftMotor_MSGTYPE TT_MotorParameters
#define GV_struct_define_RightMotor_MSGTYPE TT_MotorParameters
#define GV_struct_define_SwingMotor_MSGTYPE TT_MotorParameters
#define GV_struct_define_TL720DParameters_MSGTYPE MSP_TL720DParameters
#define GV_struct_define_IO_MSGTYPE IO_Data
#define GV_struct_define_SystemErrorData_MSGTYPE ErrorData
#define GV_struct_define_PV_MSGTYPE PV_struct_define
#define GV_struct_define_Strain_Gauge_MSGTYPE Strain_Gauge_Struct
#define GV_struct_define_GroundManagementValue_MSGTYPE ground_management_struct
extern const pb_msgdesc_t GV_struct_define_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define GV_struct_define_fields &GV_struct_define_msg
/* Maximum encoded size of messages (where known) */
#define BSP_GV_PB_H_MAX_SIZE GV_struct_define_size
#define GV_struct_define_size 2004
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

58
Bingoo/include/base/bsp_IAP.pb.h

@ -0,0 +1,58 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_IAP_PB_H_INCLUDED
#define PB_BSP_IAP_PB_H_INCLUDED
#include "pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
/* IAP,即In Application Programming,IAP是用户自己的程序在运行过程中对User Flash的部分区域进行烧写。 */
typedef struct _IAP_struct_define {
int32_t Total_Bytes; /* all the received data; */
int32_t NextCodeVrsion; /* the New upgrade Version of the Project */
int32_t UtcTime; /* Udgrade Time */
int32_t UpgradeSucceeded; /* */
} IAP_struct_define;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define IAP_struct_define_init_default {0, 0, 0, 0}
#define IAP_struct_define_init_zero {0, 0, 0, 0}
/* Field tags (for use in manual encoding/decoding) */
#define IAP_struct_define_Total_Bytes_tag 1
#define IAP_struct_define_NextCodeVrsion_tag 2
#define IAP_struct_define_UtcTime_tag 3
#define IAP_struct_define_UpgradeSucceeded_tag 4
/* Struct field encoding specification for nanopb */
#define IAP_struct_define_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, Total_Bytes, 1) \
X(a, STATIC, SINGULAR, INT32, NextCodeVrsion, 2) \
X(a, STATIC, SINGULAR, INT32, UtcTime, 3) \
X(a, STATIC, SINGULAR, INT32, UpgradeSucceeded, 4)
#define IAP_struct_define_CALLBACK NULL
#define IAP_struct_define_DEFAULT NULL
extern const pb_msgdesc_t IAP_struct_define_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define IAP_struct_define_fields &IAP_struct_define_msg
/* Maximum encoded size of messages (where known) */
#define BSP_IAP_PB_H_MAX_SIZE IAP_struct_define_size
#define IAP_struct_define_size 44
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

81
Bingoo/include/base/bsp_IO.pb.h

@ -0,0 +1,81 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_IO_PB_H_INCLUDED
#define PB_BSP_IO_PB_H_INCLUDED
#include "pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
typedef struct _IO_Data {
int32_t DO0;
int32_t DO1;
int32_t DO2;
int32_t DO3;
int32_t DO4;
int32_t DO5;
int32_t DI0;
int32_t DI1;
int32_t DI2;
int32_t DI3;
int32_t DI4;
int32_t DI5;
} IO_Data;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define IO_Data_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define IO_Data_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
/* Field tags (for use in manual encoding/decoding) */
#define IO_Data_DO0_tag 1
#define IO_Data_DO1_tag 2
#define IO_Data_DO2_tag 3
#define IO_Data_DO3_tag 4
#define IO_Data_DO4_tag 5
#define IO_Data_DO5_tag 6
#define IO_Data_DI0_tag 7
#define IO_Data_DI1_tag 8
#define IO_Data_DI2_tag 9
#define IO_Data_DI3_tag 10
#define IO_Data_DI4_tag 11
#define IO_Data_DI5_tag 12
/* Struct field encoding specification for nanopb */
#define IO_Data_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, DO0, 1) \
X(a, STATIC, SINGULAR, INT32, DO1, 2) \
X(a, STATIC, SINGULAR, INT32, DO2, 3) \
X(a, STATIC, SINGULAR, INT32, DO3, 4) \
X(a, STATIC, SINGULAR, INT32, DO4, 5) \
X(a, STATIC, SINGULAR, INT32, DO5, 6) \
X(a, STATIC, SINGULAR, INT32, DI0, 7) \
X(a, STATIC, SINGULAR, INT32, DI1, 8) \
X(a, STATIC, SINGULAR, INT32, DI2, 9) \
X(a, STATIC, SINGULAR, INT32, DI3, 10) \
X(a, STATIC, SINGULAR, INT32, DI4, 11) \
X(a, STATIC, SINGULAR, INT32, DI5, 12)
#define IO_Data_CALLBACK NULL
#define IO_Data_DEFAULT NULL
extern const pb_msgdesc_t IO_Data_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define IO_Data_fields &IO_Data_msg
/* Maximum encoded size of messages (where known) */
#define BSP_IO_PB_H_MAX_SIZE IO_Data_size
#define IO_Data_size 132
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

147
Bingoo/include/base/bsp_IV.pb.h

@ -0,0 +1,147 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_IV_PB_H_INCLUDED
#define PB_BSP_IV_PB_H_INCLUDED
#include "pb.h"
#include "bsp_PV.pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
/* 抛丸机器人状态采集参数结构体(IV:Input/Status Value)
APP/ */
typedef struct _IV_struct_define {
/* 左侧补偿值(摆臂/位置角度补偿)
÷ 100 = °100 1°250 2.5° */
int32_t LeftCompensation;
/* 右侧补偿值(摆臂/位置角度补偿)
÷ 100 = °100 1°300 3° */
int32_t RightCompensation;
/* 机器人实际移动速度(派生采集值)
÷ 10 = m/min100 10m/min180 18m/min
0~18m/min的速度范围 */
int32_t Robot_Move_Deri_Speed;
/* 机器人陀螺仪角度(姿态检测)
÷ 100 = °100 1°9000 90°
姿//姿 */
int32_t Robot_Gyro;
/* 距离传感器采集值(测距/避障)
÷ 10 = cm100 10cm500 50cm
/ */
int32_t Distance_Sensor;
/* 系统级错误码
0 = 0 =
*/
int32_t SystemError;
/* 左轮电机报警状态
0 = 1 = //
*/
int32_t Left_Motor_Err;
/* 右轮电机报警状态
0 = 1 = //
*/
int32_t Right_Motor_Err;
/* 摆臂电机报警状态
0 = 1 = //
/25°/S的作业要求 */
int32_t Swing_Motor_Err;
/* 机器人在线状态
0 = 线1 = 线
APP/线 */
int32_t Is_Online;
/* 备用数据1
/ */
int32_t Spara_Data_1;
/* 备用数据2
/ */
int32_t Spara_Data_2;
/* 备用数据3
/ */
int32_t Spara_Data_3;
/* 焊缝数据 */
int32_t Weld_data;
/* 焊缝是否存在 */
int32_t Weld_exist;
/* 回转中心偏距 */
int32_t Turn_difference;
/* 当前压力 */
int32_t Present_press;
int32_t left_angle;
int32_t right_angle;
/* 检测机器人是否到达设定的启动时间 */
int32_t robot_start;
} IV_struct_define;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define IV_struct_define_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define IV_struct_define_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
/* Field tags (for use in manual encoding/decoding) */
#define IV_struct_define_LeftCompensation_tag 1
#define IV_struct_define_RightCompensation_tag 2
#define IV_struct_define_Robot_Move_Deri_Speed_tag 3
#define IV_struct_define_Robot_Gyro_tag 4
#define IV_struct_define_Distance_Sensor_tag 5
#define IV_struct_define_SystemError_tag 6
#define IV_struct_define_Left_Motor_Err_tag 7
#define IV_struct_define_Right_Motor_Err_tag 8
#define IV_struct_define_Swing_Motor_Err_tag 9
#define IV_struct_define_Is_Online_tag 10
#define IV_struct_define_Spara_Data_1_tag 11
#define IV_struct_define_Spara_Data_2_tag 12
#define IV_struct_define_Spara_Data_3_tag 13
#define IV_struct_define_Weld_data_tag 14
#define IV_struct_define_Weld_exist_tag 15
#define IV_struct_define_Turn_difference_tag 16
#define IV_struct_define_Present_press_tag 17
#define IV_struct_define_left_angle_tag 18
#define IV_struct_define_right_angle_tag 19
#define IV_struct_define_robot_start_tag 20
/* Struct field encoding specification for nanopb */
#define IV_struct_define_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, LeftCompensation, 1) \
X(a, STATIC, SINGULAR, INT32, RightCompensation, 2) \
X(a, STATIC, SINGULAR, INT32, Robot_Move_Deri_Speed, 3) \
X(a, STATIC, SINGULAR, INT32, Robot_Gyro, 4) \
X(a, STATIC, SINGULAR, INT32, Distance_Sensor, 5) \
X(a, STATIC, SINGULAR, INT32, SystemError, 6) \
X(a, STATIC, SINGULAR, INT32, Left_Motor_Err, 7) \
X(a, STATIC, SINGULAR, INT32, Right_Motor_Err, 8) \
X(a, STATIC, SINGULAR, INT32, Swing_Motor_Err, 9) \
X(a, STATIC, SINGULAR, INT32, Is_Online, 10) \
X(a, STATIC, SINGULAR, INT32, Spara_Data_1, 11) \
X(a, STATIC, SINGULAR, INT32, Spara_Data_2, 12) \
X(a, STATIC, SINGULAR, INT32, Spara_Data_3, 13) \
X(a, STATIC, SINGULAR, INT32, Weld_data, 14) \
X(a, STATIC, SINGULAR, INT32, Weld_exist, 15) \
X(a, STATIC, SINGULAR, INT32, Turn_difference, 16) \
X(a, STATIC, SINGULAR, INT32, Present_press, 17) \
X(a, STATIC, SINGULAR, INT32, left_angle, 18) \
X(a, STATIC, SINGULAR, INT32, right_angle, 19) \
X(a, STATIC, SINGULAR, INT32, robot_start, 20)
#define IV_struct_define_CALLBACK NULL
#define IV_struct_define_DEFAULT NULL
extern const pb_msgdesc_t IV_struct_define_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define IV_struct_define_fields &IV_struct_define_msg
/* Maximum encoded size of messages (where known) */
#define BSP_IV_PB_H_MAX_SIZE IV_struct_define_size
#define IV_struct_define_size 225
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

52
Bingoo/include/base/bsp_MB_host.h

@ -0,0 +1,52 @@
#ifndef __BSP_MB_HOST_H__
#define __BSP_MB_HOST_H__
/* 包含头文件 ----------------------------------------------------------------*/
/* 类型定义 ------------------------------------------------------------------*/
/* 宏定义 --------------------------------------------------------------------*/
#define MB_SLAVEADDR 0x0001 //从机地址
#define MB_REG_ADDR 0 //寄存器地址(离散、线圈)
#define HoldingReg 0 //保持寄存器
#define InputRegReg 0x0020 //输入寄存器
#define SWAP_ENDIAN_16(x) (((x) >> 8) | ((x) << 8))
#include "bsp_include.h"
#include "BSP/bsp_UART.h"
/* 扩展变量 ------------------------------------------------------------------*/
typedef struct
{
uint16_t DATA_01H;
uint16_t DATA_02H;
uint16_t DATA_03H;
uint16_t DATA_04H;
uint16_t DATA_05H;
uint16_t DATA_06H;
uint8_t DATA_10H[64];
}MB_REG_DATA;
//;
extern uint8_t MB_rx_flag;
extern uint16_t Read_Reg_Num;
/* 函数声明 ------------------------------------------------------------------*/
uint16_t MB_CRC16(uint8_t *pushMsg, uint16_t usDataLen);
void MB_ReadCoil(uint8_t* Tx_Buf,uint8_t* TxCount_t,uint8_t _addr, uint16_t _reg, uint16_t _num);
void MB_WriteCoil(uint8_t* Tx_Buf,uint8_t* TxCount_t,uint8_t _addr, uint16_t _reg, uint16_t _sta);
void MB_ReadInput(uint8_t* Tx_Buf,uint8_t* TxCount_t,uint8_t _addr, uint16_t _reg, uint16_t _num);
void MB_ReadHoldingReg(uint8_t* Tx_Buf,uint8_t* TxCount_t,uint8_t _addr, uint16_t _reg, uint16_t _num);
void MB_ReadInputReg(uint8_t* Tx_Buf,uint8_t* TxCount_t,uint8_t _addr, uint16_t _reg, uint16_t _num);
void MB_WriteHoldingReg(uint8_t* Tx_Buf,uint8_t* TxCount_t,uint8_t _addr, uint16_t _reg, uint16_t _data);
//void MB_WriteNumHoldingReg(uint8_t* Tx_Buf,uint8_t* TxCount_t,uint8_t _addr, uint16_t _reg, uint16_t _num,uint8_t *_databuf)
void MB_WriteNumHoldingReg(uint8_t* Tx_Buf,uint8_t* TxCount_t,uint8_t _addr, uint16_t _reg, uint16_t _num,uint8_t *_databuf);
void MB_WriteNumCoil(uint8_t *Tx_Buf, uint8_t *TxCount_t, uint8_t _addr,
uint16_t _reg, uint16_t _num, uint8_t *_databuf);
#endif /* __BSP_MB_HOST_H__ */
/******************* (C) COPYRIGHT 2015-2020 硬石嵌入式开发团队 *****END OF FILE****/

57
Bingoo/include/base/bsp_PID.pb.h

@ -0,0 +1,57 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_PID_PB_H_INCLUDED
#define PB_BSP_PID_PB_H_INCLUDED
#include "pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
typedef struct _PID_Parameters {
int32_t PID_Angle; /* 调整 单位0.01° 配置时需要*100 */
double Kp; /* PID参数 */
double Ki;
double Kd;
} PID_Parameters;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define PID_Parameters_init_default {0, 0, 0, 0}
#define PID_Parameters_init_zero {0, 0, 0, 0}
/* Field tags (for use in manual encoding/decoding) */
#define PID_Parameters_PID_Angle_tag 1
#define PID_Parameters_Kp_tag 2
#define PID_Parameters_Ki_tag 3
#define PID_Parameters_Kd_tag 4
/* Struct field encoding specification for nanopb */
#define PID_Parameters_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, PID_Angle, 1) \
X(a, STATIC, SINGULAR, DOUBLE, Kp, 2) \
X(a, STATIC, SINGULAR, DOUBLE, Ki, 3) \
X(a, STATIC, SINGULAR, DOUBLE, Kd, 4)
#define PID_Parameters_CALLBACK NULL
#define PID_Parameters_DEFAULT NULL
extern const pb_msgdesc_t PID_Parameters_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define PID_Parameters_fields &PID_Parameters_msg
/* Maximum encoded size of messages (where known) */
#define BSP_PID_PB_H_MAX_SIZE PID_Parameters_size
#define PID_Parameters_size 38
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

136
Bingoo/include/base/bsp_PV.pb.h

@ -0,0 +1,136 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_PV_PB_H_INCLUDED
#define PB_BSP_PV_PB_H_INCLUDED
#include "pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
/* 抛丸机器人作业参数结构体定义
APP/ */
typedef struct _PV_struct_define {
/* 操作模式(枚举值)
1 - /
2 - /
3 - "平民""平面"
4 -
5 -
6 -
7 - */
int32_t Robot_Operation_Mode;
/* 机器人移动速度(基础行走速度)
0.1m/min×0.1=101m/min
0~1800~18m/min18m/min的要求 */
int32_t Robot_Move_Speed;
/* 换道距离(自动换道功能的核心参数)
mm
*/
int32_t Robot_Change_Lane_Distance;
/* 摆臂速度(抛丸/喷砂摆臂装置的摆动速度)
°/s/
2525°/S的要求 */
int32_t Robot_Swing_Speed;
/* 摆臂角度设置模式(对称/非对称)
1 -
2 - / */
int32_t Robot_symmetricalOrNot;
/* 对称模式下摆臂总摆动角度
°
90-45°~+45° */
int32_t Robot_Swing_Range_Angle;
/* 非对称模式下的摆动侧选择
1 -
2 - */
int32_t Robot_asymmetricalAngleSetValue;
/* 后退作业模式(抛丸/喷砂作业时的后退逻辑)
1 - 退退
2 - 退退 */
int32_t Robot_backMode;
/* 打退交替模式下的后退距离
mm
退退 */
int32_t Robot_Back_Distance;
/* 边打边退模式下的后退速度
0.1m/minRobot_Move_Speed
0~1800~18m/min */
int32_t Robot_Back_Speed;
/* 压力设置(抛丸/喷砂作业的介质压力)
0.01MPa500.5MPa
/Sa2.5 */
int32_t Robot_Press_Set;
/* 竖直微调(竖直作业模式下的位置微调量)
mm
/ */
int32_t Robot_Vertical_Adjust;
/* 自动模式下的作业长度
mm
*/
int32_t Robot_Length_Homework;
/* 自动模式下的作业宽度
mm
110mm标准作业宽度 */
int32_t Robot_Width_Homework;
} PV_struct_define;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define PV_struct_define_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define PV_struct_define_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
/* Field tags (for use in manual encoding/decoding) */
#define PV_struct_define_Robot_Operation_Mode_tag 1
#define PV_struct_define_Robot_Move_Speed_tag 2
#define PV_struct_define_Robot_Change_Lane_Distance_tag 3
#define PV_struct_define_Robot_Swing_Speed_tag 4
#define PV_struct_define_Robot_symmetricalOrNot_tag 5
#define PV_struct_define_Robot_Swing_Range_Angle_tag 6
#define PV_struct_define_Robot_asymmetricalAngleSetValue_tag 7
#define PV_struct_define_Robot_backMode_tag 8
#define PV_struct_define_Robot_Back_Distance_tag 9
#define PV_struct_define_Robot_Back_Speed_tag 10
#define PV_struct_define_Robot_Press_Set_tag 11
#define PV_struct_define_Robot_Vertical_Adjust_tag 12
#define PV_struct_define_Robot_Length_Homework_tag 13
#define PV_struct_define_Robot_Width_Homework_tag 14
/* Struct field encoding specification for nanopb */
#define PV_struct_define_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, Robot_Operation_Mode, 1) \
X(a, STATIC, SINGULAR, INT32, Robot_Move_Speed, 2) \
X(a, STATIC, SINGULAR, INT32, Robot_Change_Lane_Distance, 3) \
X(a, STATIC, SINGULAR, INT32, Robot_Swing_Speed, 4) \
X(a, STATIC, SINGULAR, INT32, Robot_symmetricalOrNot, 5) \
X(a, STATIC, SINGULAR, INT32, Robot_Swing_Range_Angle, 6) \
X(a, STATIC, SINGULAR, INT32, Robot_asymmetricalAngleSetValue, 7) \
X(a, STATIC, SINGULAR, INT32, Robot_backMode, 8) \
X(a, STATIC, SINGULAR, INT32, Robot_Back_Distance, 9) \
X(a, STATIC, SINGULAR, INT32, Robot_Back_Speed, 10) \
X(a, STATIC, SINGULAR, INT32, Robot_Press_Set, 11) \
X(a, STATIC, SINGULAR, INT32, Robot_Vertical_Adjust, 12) \
X(a, STATIC, SINGULAR, INT32, Robot_Length_Homework, 13) \
X(a, STATIC, SINGULAR, INT32, Robot_Width_Homework, 14)
#define PV_struct_define_CALLBACK NULL
#define PV_struct_define_DEFAULT NULL
extern const pb_msgdesc_t PV_struct_define_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define PV_struct_define_fields &PV_struct_define_msg
/* Maximum encoded size of messages (where known) */
#define BSP_PV_PB_H_MAX_SIZE PV_struct_define_size
#define PV_struct_define_size 154
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

80
Bingoo/include/base/bsp_ReCmd.pb.h

@ -0,0 +1,80 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_RECMD_PB_H_INCLUDED
#define PB_BSP_RECMD_PB_H_INCLUDED
#include "pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
/* this message is used for the reply the command */
typedef struct _ReCmd {
int32_t CommadNum;
/* 定义 1 上位机获取默认CV值
2 CV值
3 CV值
4 Trace等级值
5
6 0
7
8
9 Parameter0 Parameter0
Buff_Data_Length */
int32_t Parameter0;
int32_t Parameter1;
int32_t Parameter2;
int32_t Parameter3;
int32_t Parameter4;
int32_t Buff_Data_Length;
pb_byte_t Buff_Data[512];
} ReCmd;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define ReCmd_init_default {0, 0, 0, 0, 0, 0, 0, {0}}
#define ReCmd_init_zero {0, 0, 0, 0, 0, 0, 0, {0}}
/* Field tags (for use in manual encoding/decoding) */
#define ReCmd_CommadNum_tag 1
#define ReCmd_Parameter0_tag 2
#define ReCmd_Parameter1_tag 3
#define ReCmd_Parameter2_tag 4
#define ReCmd_Parameter3_tag 5
#define ReCmd_Parameter4_tag 6
#define ReCmd_Buff_Data_Length_tag 7
#define ReCmd_Buff_Data_tag 8
/* Struct field encoding specification for nanopb */
#define ReCmd_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, CommadNum, 1) \
X(a, STATIC, SINGULAR, INT32, Parameter0, 2) \
X(a, STATIC, SINGULAR, INT32, Parameter1, 3) \
X(a, STATIC, SINGULAR, INT32, Parameter2, 4) \
X(a, STATIC, SINGULAR, INT32, Parameter3, 5) \
X(a, STATIC, SINGULAR, INT32, Parameter4, 6) \
X(a, STATIC, SINGULAR, INT32, Buff_Data_Length, 7) \
X(a, STATIC, SINGULAR, FIXED_LENGTH_BYTES, Buff_Data, 8)
#define ReCmd_CALLBACK NULL
#define ReCmd_DEFAULT NULL
extern const pb_msgdesc_t ReCmd_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define ReCmd_fields &ReCmd_msg
/* Maximum encoded size of messages (where known) */
#define BSP_RECMD_PB_H_MAX_SIZE ReCmd_size
#define ReCmd_size 592
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

63
Bingoo/include/base/bsp_TCPClient.h

@ -0,0 +1,63 @@
/*
* bsp_TCPClient.h
*
* Created on: Oct 22, 2024
* Author: akeguo
*/
#ifndef INC_BSP_BSP_TCPCLIENT_H_
#define INC_BSP_BSP_TCPCLIENT_H_
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
#define USE_LCD /* enable LCD */
#define DEST_IP_ADDR0 ((uint8_t)192U)
#define DEST_IP_ADDR1 ((uint8_t)168U)
#define DEST_IP_ADDR2 ((uint8_t)1U)
#define DEST_IP_ADDR3 ((uint8_t)10U)
#define DEST_PORT ((uint16_t)502U)
/*NETMASK*/
#define NETMASK_ADDR0 ((uint8_t) 255U)
#define NETMASK_ADDR1 ((uint8_t) 255U)
#define NETMASK_ADDR2 ((uint8_t) 255U)
#define NETMASK_ADDR3 ((uint8_t) 0U)
/*Gateway Address*/
#define GW_ADDR0 ((uint8_t) 192U)
#define GW_ADDR1 ((uint8_t) 168U)
#define GW_ADDR2 ((uint8_t) 1U)
#define GW_ADDR3 ((uint8_t) 1U)
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
//void tcp_client_connect(void);
typedef struct _LazorData
{
float Feature_X; //特征点X
float Feature_Y; //特征点Y
float Feature_Z; //特征点Z
float Gap; //间隙
float WrongEdgeQuantity; //错边量
float Area; //面积
} LazorData;
extern unsigned char *Weld_Out_Flag;
extern unsigned char Weld_Out_Count;
extern unsigned char Weld_Out_SafeCount;
extern LazorData *ReadLazorData;
void TCP_Client_Init(void);
#endif /* INC_BSP_BSP_TCPCLIENT_H_ */

17
Bingoo/include/base/bsp_TIMER.h

@ -0,0 +1,17 @@
/*
* bsp_TIMER.h
*
* Created on: Oct 26, 2023
* Author: shiya
*/
#ifndef INC_BSP_TIMER_H_
#define INC_BSP_TIMER_H_
#include "BSP/bsp_TCPClient.h"
#include "bsp_include.h"
uint8_t GF_BSP_TIMER_Init(void);
void GF_BSP_TIMER_DelayUS(uint32_t n);
#endif /* INC_BSP_TIMER_H_ */

109
Bingoo/include/base/bsp_UART.h

@ -0,0 +1,109 @@
#ifndef INC_BSP_UART_H_
#define INC_BSP_UART_H_
#include "BSP/bsp_include.h"
#include "main.h"
#include "bsp_Error.pb.h"
#define UART_Transmit_MAX_NUM 1024
#define UART_Receive_MAX_NUM 100
extern struct UARTHandler RS_485_1_UART_Handler;
extern struct UARTHandler RS_485_2_UART_Handler;
extern struct UARTHandler RS_485_3_UART_Handler;
extern struct UARTHandler RS_485_4_UART_Handler;
extern struct UARTHandler InterCall_DEBUG_UART_Handler;
extern struct UARTHandler E28_SBUS_UART_Handler;
extern struct UARTHandler LTE_7S0_Serial_UART_Handler;
#if defined (hlpuart1Exit)
extern struct UARTHandler LPUART1_UART_Handler;
#endif
uint8_t GF_BSP_UART_Init(void);
void GF_BSP_UARTHandlers_Intialize(
int32_t RS485_1_WaitTime,
int32_t RS485_2_WaitTime,
int32_t RS485_3_WaitTime,
int32_t RS485_4_WaitTime,
int32_t LTE_7S0_Serial_WaitTime,
int32_t InterCall_DEBUG_WaitTime,
int32_t E28_SBUS_WaitTime,
int32_t LPUART1_UART_WaitTime,
int32_t RS485_1_Dispacher_Time,
int32_t RS485_2_Dispacher_Time,
int32_t RS485_3_Dispacher_Time,
int32_t RS485_4_Dispacher_Time,
int32_t LTE_7S0_Serial_Dispacher_Time,
int32_t InterCall_DEBUG_Dispacher_Time,
int32_t E28_SBUS_Dispacher_Time,
int32_t LPUART1_UART_Dispacher_Time
);
//串行发送完成后才能发送第二帧数据,没有做缓冲,如未发送完成,第二次发送无效,丢弃发送数据
void GF_BSP_UART_Transmit(const uint8_t RS485_Index,const uint8_t *pData, uint16_t Size);
typedef struct UARTSendHandler
{
uint16_t SendLength;
uint16_t SendListTimePeriod;
uint8_t Tx_Buf[502];
void (*UART_Decode)(uint8_t*, uint16_t); // 发送缓存
struct UARTSendHandler* pNext;
}UARTSendHandler;
struct UARTHandler
{
char startCountFlag; //indicate that to start counting
char send_finished;//indicate decode finished or not
char decode_finished;//indicate decode finished or not
uint8_t tmp_Rx_Buf[2]; // temporary data to store received data
uint32_t Wait_time; // the time to wait
//uint32_t Send_time;
//uint32_t count;
uint32_t Wait_Time_Count;
uint32_t SendList_time_Count;
uint32_t SendList_Period;
uint8_t SendListExists;
UART_HandleTypeDef* uart; //UART to use
unsigned char timeSpan; // timer elapsed time
uint8_t Rx_Buf[2048]; // 接收缓存,最大256字节
uint8_t Tx_Buf[2048]; //发送缓存 157,864
uint16_t TxCount;
uint16_t RxCount;
//(UART_HandleTypeDef *huart, const uint8_t *pData, uint16_t Size)
void (*UART_Tx)(struct UARTHandler*); //void UART_Tx(uint8_t *Tx_Buf,uint16_t TxCount);
void (*UART_Rx)(struct UARTHandler*);
void (*UART_Decode)(uint8_t*, uint16_t); //Decode Rx_Buf
UARTSendHandler *pCurrentUARTSendHadler; //
void (*AddSendList)(struct UARTHandler*, uint8_t*, uint16_t,uint32_t,//这里是修改等待时间
void (*UART_Decode)(uint8_t*, uint16_t));
struct _DispacherController *dispacherController;
};
void UARTHandlerTx(struct UARTHandler *uartHandler);
void UARTHandlerRX(struct UARTHandler *uartHandler);
//void IntializeUARTHandler(struct UARTHandler *uartHandler, UART_HandleTypeDef uart,int32_t WaitTime,unsigned char timeSpan);
void Counting(struct UARTHandler *uartHandler);
void IntializeUARTHandler(struct UARTHandler *uartHandler,
UART_HandleTypeDef *uart, int32_t WaitTime, unsigned char timeSpan,int32_t Dispacher_Time);
void GF_BSP_UART_Timer();
#endif /* INC_BSP_UART_H_ */

23
Bingoo/include/base/bsp_UDP.h

@ -0,0 +1,23 @@
/*
* bsp_UDP.h
*
* Created on: Aug 13, 2024
* Author: akeguo
*/
#ifndef INC_BSP_BSP_UDP_H_
#define INC_BSP_BSP_UDP_H_
void udp_client_init(void);
void udp_dlt_send_back(char *pData,uint16_t Size);
void udp_cmd_send_back(char *pData, uint16_t Size);
typedef void (*DLT_DecodeFuncPtr)(uint8_t*, uint16_t);
void udp_send_by_pcb(struct udp_pcb * upcb,char *pData, uint16_t Size);
// 再用该类型声明变量
extern DLT_DecodeFuncPtr UDP_DLT_ReceivedCallback;
extern int8_t is_udp_GV_update_loop_enalbed;
#endif /* INC_BSP_BSP_UDP_H_ */

27
Bingoo/include/base/bsp_UpperComputer_Handler.h

@ -0,0 +1,27 @@
/*
* bsp_desulfurizer_handler.h
*
* Created on: Jul 29, 2024
* Author: akeguo
*/
#ifndef INC_BSP_BSP_UPPERCOMPUTER_HANDLER_H_
#define INC_BSP_BSP_UPPERCOMPUTER_HANDLER_H_
#include <stdio.h>
#include <string.h>
#include "bsp_MB_host.h"
#include "stdio.h"
#include "BSP/bsp_UART.h"
#include "usart.h"
#include "gpio.h"
extern struct UARTHandler *desulfurizer_message_UART_Handler;
void upper_Computer_UART_Handler_intialize(struct UARTHandler *Handler);
void decode_command_from_computer(uint8_t *buffer, uint16_t length);
void send_data_to_upper_computer(double Angle, double WireLength,
double Thickness, char IsFittingPoint,char isMqtt,struct UARTHandler *send_UART_Handler);
#endif /* INC_BSP_BSP_UPPERCOMPUTER_HANDLER_H_ */

13
Bingoo/include/base/bsp_client_setting.h

@ -0,0 +1,13 @@
/*
* bsp_pv_setting.h
*
* Created on: Jan 8, 2025
* Author: akeguo
*/
#ifndef INC_BSP_BSP_CLIENT_SETTING_H_
#define INC_BSP_BSP_CLIENT_SETTING_H_
#include "BHBF_ROBOT.h"
void client_setting_intialize(struct UARTHandler *Handler);
#endif /* INC_BSP_BSP_CLIENT_SETTING_H_ */

82
Bingoo/include/base/bsp_com_helper.h

@ -0,0 +1,82 @@
/*
* bsp_com_helper.h
*
* Created on: Oct 9, 2024
* Author: akeguo
*/
#ifndef INC_BSP_BSP_COM_HELPER_H_
#define INC_BSP_BSP_COM_HELPER_H_
#include "bsp_include.h"
typedef struct _Dispatcher
{
//uint8_t IsDeleted;
void (*dispache)(void);
//struct _Dispatcher* pBefore;
struct _Dispatcher* pNext;
}Dispatcher;
//通讯链表节点结构体
typedef struct _ComHardWare
{
//void (*dispache)(void);
char Name[50];
char IsOnline;
uint32_t BitFlag;
struct _ComHardWare* pNext;
}ComHardWare;
typedef struct _DispacherController
{
Dispatcher *pHead; // = NULL; //环形链表中的数据头指针
Dispatcher *pTail; // = NULL; //环形链表中的数据尾指针
uint16_t DispacherNumber; // = 0;
uint16_t DispacherCallTime; //
uint16_t Dispacher_Counter; // = 0;
uint16_t Dispacher_Enable; // = 0 disable 1 enable
void (*Add_Dispatcher_List)(struct _DispacherController* ,
void (*dispacher)(void)); //UART的调度程序
void (*Dispatcher_Run)(struct _DispacherController* ); //UART的调度程序
}DispacherController;
typedef struct _HardWareController
{
struct _ComHardWare *pComHWHead;
struct _ComHardWare *pComHWTail;
uint16_t HardWare_Check_Counter;
uint16_t DispacherCallTime; //= 100; //2ms 一次,
void (*Add_PCOMHardWare)(struct _HardWareController *, char* , char ,uint32_t);
void (*PCOMHardWare_Check)(struct _HardWareController *);
int (*Set_PCOMHardWare)(struct _HardWareController *, char* , char );
} HardWareController;
void Dispatch_t(DispacherController *uartHandler);
void Dispatcher_List_Add_t(DispacherController *uartHandler,void (*dispache)(void));
// void Dispatcher_List_Add_t(DispacherController *uartHandler,
// void (*dispache)(void),void (*Decode)(uint8_t*, uint16_t));
// void ComHardWare_List_Add_t(HardWareController *uartHandler, char *name,char value);
void PCOMHardWare_Check_t(HardWareController *uartHandler);
int Set_PCOMHardWare_t(HardWareController *uartHandler, char *name, char value);
void ComHardWare_List_Add_t(HardWareController *uartHandler, char *name,
char value,uint32_t bitFlag);
#endif /* INC_BSP_BSP_COM_HELPER_H_ */

66
Bingoo/include/base/bsp_cpu_flash.h

@ -0,0 +1,66 @@
/*
* bsp_cpu_flash.h
*
* Created on: Aug 28, 2024
* Author: akeguo
*/
#ifndef SRC_BSP_BSP_CPU_FLASH_H_
#define SRC_BSP_BSP_CPU_FLASH_H_
#include "main.h"
#include <bsp_qspi_w25q128.h>
#include "quadspi.h"
#define ENABLE_INT() __set_PRIMASK(0) /* 使能全局中断 */
#define DISABLE_INT() __set_PRIMASK(1) /* 禁止全局中断 */
#define CPU_FLASH_BASE_ADDR (uint32_t)(FLASH_BASE) /* 0x08000000 */
#define CPU_FLASH_END_ADDR (uint32_t)(0x081FFFFF)
#define CPU_FLASH_SIZE (2 * 1024 * 1024) /* FLASH总容量 */
#define CPU_FLASH_SECTOR_SIZE (128 * 1024) /* 扇区大小,字节 */
/* Base address of the Flash sectors Bank 1 */
#define ADDR_FLASH_SECTOR_0_BANK1 ((uint32_t)0x08000000) /* Base @ of Sector 0, 128 Kbytes */
#define ADDR_FLASH_SECTOR_1_BANK1 ((uint32_t)0x08020000) /* Base @ of Sector 1, 128 Kbytes */
#define ADDR_FLASH_SECTOR_2_BANK1 ((uint32_t)0x08040000) /* Base @ of Sector 2, 128 Kbytes */
#define ADDR_FLASH_SECTOR_3_BANK1 ((uint32_t)0x08060000) /* Base @ of Sector 3, 128 Kbytes */
#define ADDR_FLASH_SECTOR_4_BANK1 ((uint32_t)0x08080000) /* Base @ of Sector 4, 128 Kbytes */
#define ADDR_FLASH_SECTOR_5_BANK1 ((uint32_t)0x080A0000) /* Base @ of Sector 5, 128 Kbytes */
#define ADDR_FLASH_SECTOR_6_BANK1 ((uint32_t)0x080C0000) /* Base @ of Sector 6, 128 Kbytes */
#define ADDR_FLASH_SECTOR_7_BANK1 ((uint32_t)0x080E0000) /* Base @ of Sector 7, 128 Kbytes */
/* Base address of the Flash sectors Bank 2 */
#define ADDR_FLASH_SECTOR_0_BANK2 ((uint32_t)0x08100000) /* Base @ of Sector 0, 128 Kbytes */
#define ADDR_FLASH_SECTOR_1_BANK2 ((uint32_t)0x08120000) /* Base @ of Sector 1, 128 Kbytes */
#define ADDR_FLASH_SECTOR_2_BANK2 ((uint32_t)0x08140000) /* Base @ of Sector 2, 128 Kbytes */
#define ADDR_FLASH_SECTOR_3_BANK2 ((uint32_t)0x08160000) /* Base @ of Sector 3, 128 Kbytes */
#define ADDR_FLASH_SECTOR_4_BANK2 ((uint32_t)0x08180000) /* Base @ of Sector 4, 128 Kbytes */
#define ADDR_FLASH_SECTOR_5_BANK2 ((uint32_t)0x081A0000) /* Base @ of Sector 5, 128 Kbytes */
#define ADDR_FLASH_SECTOR_6_BANK2 ((uint32_t)0x081C0000) /* Base @ of Sector 6, 128 Kbytes */
#define ADDR_FLASH_SECTOR_7_BANK2 ((uint32_t)0x081E0000) /* Base @ of Sector 7, 128 Kbytes */
#define FLASH_IS_EQU 0 /* Flash内容和待写入的数据相等,不需要擦除和写操作 */
#define FLASH_REQ_WRITE 1 /* Flash不需要擦除,直接写 */
#define FLASH_REQ_ERASE 2 /* Flash需要先擦除,再写 */
#define FLASH_PARAM_ERR 3 /* 函数参数错误 */
#define App_Start_Addr 0x08000000
#define App_Run_Addr 0x08020000
#define App_Download_Addr 0x08080000 // ADDR_FLASH_SECTOR_4_BANK1
uint8_t bsp_ReadCpuFlash(uint32_t _ulFlashAddr, uint8_t *_ucpDst, uint32_t _ulSize);
uint8_t bsp_WriteCpuFlash(uint32_t _ulFlashAddr, uint8_t *_ucpSrc, uint32_t _ulSize);
uint8_t bsp_CmpCpuFlash(uint32_t _ulFlashAddr, uint8_t *_ucpBuf, uint32_t _ulSize);
void JumpToApp(void);
void Copy_Peripheral_Download_Flash_to_App_Start(uint32_t totalBytes);
uint8_t bsp_EraseCpuFlash(uint32_t _ulFlashAddr);
void Erase_App_Download_Flash_Addr();
void Copy_Download_Flash_to_Start();
#endif /* SRC_BSP_BSP_CPU_FLASH_H_ */

39
Bingoo/include/base/bsp_decode_command.h

@ -0,0 +1,39 @@
/*
* bsp_decode_command.h
*
* Created on: Sep 24, 2024
* Author: akeguo
*/
#ifndef INC_BSP_BSP_DECODE_COMMAND_H_
#define INC_BSP_BSP_DECODE_COMMAND_H_
#include "main.h"
#include "msp_WH_LTE_7S0.h"
#include "pb_decode.h"
#include "pb_encode.h"
#include "bsp_include.h"
#include "pb.h"
#include "bsp_Cmd.pb.h"
#include <stdio.h>
#include <stdbool.h>
#include <stdlib.h>
#include "BHBF_ROBOT.h"
#include "bsp_cpu_flash.h"
#include <bsp_qspi_w25q128.h>
#include <bsp_UpperComputer_Handler.h>
#include "bsp_ReCmd.pb.h"
#include "bsp_IV.pb.h"
void send_received_data_to_upper_computer(uint8_t *buffer, uint16_t length);
void decode_command_and_feedback(uint8_t *buffer, uint16_t length, char sendWay,
struct UARTHandler *send_Handler);
extern void WrapInCmdAndSend(ReCmd send_Cmd, uint8_t *buf, int8_t sendWay,struct UARTHandler *send_Handler);
extern void WrapInCmdAndSendMessage(ReCmd send_Cmd,int8_t functionNum,int8_t isSuccess, uint8_t *buf, int8_t sendWay,
struct UARTHandler *send_Handler);
#endif /* INC_BSP_BSP_DECODE_COMMAND_H_ */

82
Bingoo/include/base/bsp_ground_management.pb.h

@ -0,0 +1,82 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_GROUND_MANAGEMENT_PB_H_INCLUDED
#define PB_BSP_GROUND_MANAGEMENT_PB_H_INCLUDED
#include "pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
/* 从机地址0x34; */
typedef struct _ground_management_struct {
int32_t K1; /* 寄存器0:K1继电器,=0断开,=1吸合 */
int32_t K2; /* 寄存器1:K2继电器 */
int32_t K3; /* 寄存器2:K3继电器 */
int32_t K4; /* 寄存器3:K4继电器 */
int32_t K5_Default; /* 寄存器4:K5继电器的默认状态,超时寄存器5后,继电器取反(需要周期性收到其有效的modbus数据包) */
int32_t MaualControlPower; /* 手动控制开关 */
int32_t MaualPowerState; /* 手动控制开关 */
int32_t Time_Out_Period; /* 寄存器5:超时时间,毫秒 */
int32_t DMK_Speed; /* 德玛克电机速度 */
int32_t DMK_WorkState; /* 0停止 1正转 2反转 */
int32_t Save_To_Flash; /* 寄存器9:设置为55时,把当前寄存器输入存入flash,写入成功自动变成1 */
int32_t Read_Time_Out_Period; /* 从寄存器中读取的时间 */
} ground_management_struct;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define ground_management_struct_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
#define ground_management_struct_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}
/* Field tags (for use in manual encoding/decoding) */
#define ground_management_struct_K1_tag 1
#define ground_management_struct_K2_tag 2
#define ground_management_struct_K3_tag 3
#define ground_management_struct_K4_tag 4
#define ground_management_struct_K5_Default_tag 5
#define ground_management_struct_MaualControlPower_tag 6
#define ground_management_struct_MaualPowerState_tag 7
#define ground_management_struct_Time_Out_Period_tag 8
#define ground_management_struct_DMK_Speed_tag 9
#define ground_management_struct_DMK_WorkState_tag 10
#define ground_management_struct_Save_To_Flash_tag 11
#define ground_management_struct_Read_Time_Out_Period_tag 12
/* Struct field encoding specification for nanopb */
#define ground_management_struct_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, K1, 1) \
X(a, STATIC, SINGULAR, INT32, K2, 2) \
X(a, STATIC, SINGULAR, INT32, K3, 3) \
X(a, STATIC, SINGULAR, INT32, K4, 4) \
X(a, STATIC, SINGULAR, INT32, K5_Default, 5) \
X(a, STATIC, SINGULAR, INT32, MaualControlPower, 6) \
X(a, STATIC, SINGULAR, INT32, MaualPowerState, 7) \
X(a, STATIC, SINGULAR, INT32, Time_Out_Period, 8) \
X(a, STATIC, SINGULAR, INT32, DMK_Speed, 9) \
X(a, STATIC, SINGULAR, INT32, DMK_WorkState, 10) \
X(a, STATIC, SINGULAR, INT32, Save_To_Flash, 11) \
X(a, STATIC, SINGULAR, INT32, Read_Time_Out_Period, 12)
#define ground_management_struct_CALLBACK NULL
#define ground_management_struct_DEFAULT NULL
extern const pb_msgdesc_t ground_management_struct_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define ground_management_struct_fields &ground_management_struct_msg
/* Maximum encoded size of messages (where known) */
#define BSP_GROUND_MANAGEMENT_PB_H_MAX_SIZE ground_management_struct_size
#define ground_management_struct_size 132
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

57
Bingoo/include/base/bsp_include.h

@ -0,0 +1,57 @@
/*
* bsp_include.h
*
* Created on: Oct 26, 2023
* Author: shiya
*/
#ifndef INC_BSP_INCLUDE_H_
#define INC_BSP_INCLUDE_H_
#include "main.h"
#include "dma.h"
#include "fdcan.h"
#include "i2c.h"
#include "tim.h"
#include "usart.h"
#include "gpio.h"
#include "bsp_EEPROM.h"
#include "bsp_GPIO.h"
#include "bsp_FDCAN.h"
#include "bsp_TIMER.h"
#include "bsp_PV.pb.h"
#include "bsp_GV.pb.h"
#include "bsp_CV.pb.h"
#include "pb.h"
#include "pb_decode.h"
#include "pb_common.h"
#include "DLTuc.h"
//一个中断回调函数支持多少个回调函数链接
#define DF_BSP_InterCall_Num 20
//一共支持多少种中断函数
#define DF_BSP_InterCall_Type_Num 11
enum DF_BSP_InterCall_Type
{
DF_BSP_InterCall_FDCAN1_RxFifo0Callback = 0,
DF_BSP_InterCall_FDCAN2_RxFifo0Callback,
DF_BSP_InterCall_RS485_1_RxCpltCallback,
DF_BSP_InterCall_RS485_2_RxCpltCallback,
DF_BSP_InterCall_RS485_3_RxCpltCallback,
DF_BSP_InterCall_RS485_4_RxCpltCallback,
DF_BSP_InterCall_DEBUG_RxCpltCallback,
DF_BSP_InterCall_E22_Serial_RxCpltCallback,
DF_BSP_InterCall_E28_SBUS_RxFifo0Callback,
DF_BSP_InterCall_TIM1_100ms_PeriodElapsedCallback,
DF_BSP_InterCall_TIM8_2ms_PeriodElapsedCallback
};
uint8_t GF_BSP_Interrupt_Add_CallBack(enum DF_BSP_InterCall_Type _type,
void (*_fn)(void));
void GF_BSP_Interrupt_Run_CallBack(enum DF_BSP_InterCall_Type _type);
#endif /* INC_BSP_INCLUDE_H_ */

36
Bingoo/include/base/bsp_mqtt.h

@ -0,0 +1,36 @@
#ifndef __BSP_MQTT_H
#define __BSP_MQTT_H
/*-----------------------------------------------------------
* Includes files
*----------------------------------------------------------*/
/*-----------------------------------------------------------
* Exported constants
*----------------------------------------------------------*/
/*-----------------------------------------------------------
* Exported macro
*----------------------------------------------------------*/
/*-----------------------------------------------------------
* Exported function
*----------------------------------------------------------*/
/*!
* @brief MQTT
*
*
* @retval:
*/
void bsp_mqtt_init(void);
void bsp_mqtt_test(void);
extern void bsp_mqtt_pub_send(char topic[],char buf[],size_t len);
#include "bsp_pb_decode_encode.h"
#endif /* __BSP_WOLFSSL_H */

26
Bingoo/include/base/bsp_mqtt_pub.h

@ -0,0 +1,26 @@
/*
* bsp_mqtt_pub.h
*
* Created on: Jul 9, 2024
* Author: akeguo
*/
#ifndef INC_BSP_BSP_MQTT_PUB_H_
#define INC_BSP_BSP_MQTT_PUB_H_
#include "bsp_pb_decode_encode.h"
#include "pb_decode.h"
#include "pb_encode.h"
#include "bsp_CV.pb.h"
#include "bsp_pb_decode_encode.h"
#include "BSP/bsp_EEPROM.h"
extern void log_info(char logger[], char message[]);
extern void log_debug(char logger[], char message[]);
extern void log_err(char logger[], char message[]);
#endif /* INC_BSP_BSP_MQTT_PUB_H_ */

51
Bingoo/include/base/bsp_pb_decode_encode.h

@ -0,0 +1,51 @@
/*
* bsp_pb_decode_encode.h
*
* Created on: Jul 5, 2024
* Author: akeguo
*/
#ifndef INC_BSP_BSP_PB_DECODE_ENCODE_H_
#define INC_BSP_BSP_PB_DECODE_ENCODE_H_
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <stdbool.h>
#include "pb_decode.h"
#include "pb_encode.h"
#include "pb.h"
#include "bsp_CV.pb.h"
#include "bsp_GV.pb.h"
#include "msp_MK32.pb.h"
#include "msp_Motor.pb.h"
#include "bsp_PV.pb.h"
#include "bsp_CV.pb.h"
#include "bsp_CV.pb.h"
#include "pb_common.h"
#include "bsp_IAP.pb.h"
IAP_struct_define pb_decode_IAP(uint8_t *buf, size_t length);
typedef struct pb_buffer_arg
{
/* Buffer to be written, or reference to read buffer */
void const *buf;
/* Length of buf */
size_t buf_len;
} pb_buffer_arg;
bool pb_encode_string_cb(pb_ostream_t *stream, const pb_field_t *field, void *const *arg);
bool pb_decode_string_cb(pb_istream_t *stream, const pb_field_t *field, void **arg);
extern CV_struct_define pb_decode_CV(char *buf, size_t length);
extern void Test_CV();
//extern void pb_encode_TraceMessage(char buf[], size_t buf_len,size_t* len,TraceLevel traceLevel, char logger[], char message[] );
void pb_encode_TraceMessage(char buf[],size_t buf_len, size_t* len,
char traceLevel[], char logger[], char message[] );
#endif /* INC_BSP_BSP_PB_DECODE_ENCODE_H_ */

107
Bingoo/include/base/bsp_qspi_w25q128.h

@ -0,0 +1,107 @@
/*
* bsp_quadspi_W25Q128.h
*
* Created on: Apr 21, 2021
* Author: Administrator
*
* bsp用于华邦的w25q128JVw25q128JV不一样
*
*/
#ifndef BSP_QSPI_W25Q128_H_
#define BSP_QSPI_W25Q128_H_
#include "quadspi.h"
#include "stdio.h"
/* 宏定义 --------------------------------------------------------------------*/
#define FLASH_BEGIN_ADDRESS 0x00000
#define CODE_DOWNLOAD_FLASH_BEGIN_ADDRESS 0x00000
#define CODE_FLASH_STORAGE_SIZE 1024*1024 // 留下1M的空间存储数据
#define W25Q128FV_FLASH_SIZE 0x1000000 /* 128 MBits => 16MBytes */
#define W25Q128FV_BLOCK_SIZE 0x10000 /* 256 Blocks of 64KBytes */
#define W25Q128FV_HALF_BLOCK_SIZE 0x8000 /* 128 Blocks of 32KBytes */
#define W25Q128FV_SECTOR_SIZE 0x1000 /* 4096 sectors of 4kBytes */
#define W25Q128FV_PAGE_SIZE 0x100 /* 65536 pages of 256 bytes */
#define W25Q128FV_DUMMY_CYCLES_READ 4
#define W25Q128FV_DUMMY_CYCLES_READ_QUAD 10
#define W25Q128FV_BULK_ERASE_MAX_TIME 250000//ms
#define W25Q128FV_SECTOR_ERASE_MAX_TIME 3000
#define W25Q128FV_SUBSECTOR_ERASE_MAX_TIME 800
#define W25Q128FV_FLASH_ID 0XEF4018
/* W25Q128FV 指令 */
/* 复位操作 */
#define RESET_ENABLE_CMD 0x66
#define RESET_MEMORY_CMD 0x99
#define ENTER_QPI_MODE_CMD 0x38
#define EXIT_QPI_MODE_CMD 0xFF
/* 读取ID指令 */
#define READ_ID_CMD 0x90
#define DUAL_READ_ID_CMD 0x92
#define QUAD_READ_ID_CMD 0x94
#define READ_JEDEC_ID_CMD 0x9F
/* 读操作指令 */
#define READ_CMD 0x03
#define FAST_READ_CMD 0x0B
#define DUAL_OUT_FAST_READ_CMD 0x3B
#define DUAL_INOUT_FAST_READ_CMD 0xBB
#define QUAD_OUT_FAST_READ_CMD 0x6B
#define QUAD_INOUT_FAST_READ_CMD 0xEB
/* 写使能操作指令 */
#define WRITE_ENABLE_CMD 0x06
#define WRITE_DISABLE_CMD 0x04
/* 读写状态寄存器操作指令 */
#define READ_STATUS_REG1_CMD 0x05
#define READ_STATUS_REG2_CMD 0x35
#define READ_STATUS_REG3_CMD 0x15
#define WRITE_STATUS_REG1_CMD 0x01
#define WRITE_STATUS_REG2_CMD 0x31
#define WRITE_STATUS_REG3_CMD 0x11
/* 编程指令 */
#define PAGE_PROG_CMD 0x02
#define QUAD_INPUT_PAGE_PROG_CMD 0x32
/* 擦除Flash指令 */
#define SECTOR_ERASE_CMD 0x20
#define BLOCK_32KB_ERASE_CMD 0x52
#define BLOCK_64KB_ERASE_CMD 0xD8
#define CHIP_ERASE_CMD 0xC7
#define PROG_ERASE_RESUME_CMD 0x7A
#define PROG_ERASE_SUSPEND_CMD 0x75
/* 状态寄存器标志位 */
#define W25Q128FV_FSR_BUSY ((uint8_t)0x01) /* busy */
#define W25Q128FV_FSR_WREN ((uint8_t)0x02) /* write enable */
#define W25Q128FV_FSR_QE ((uint8_t)0x02) /* quad enable */
/* Flash 状态码*/
#define FLASH_OK ((uint8_t)0x00)
#define FLASH_ERROR ((uint8_t)0x01)
#define FLASH_BUSY ((uint8_t)0x02)
#define FLASH_NOT_SUPPORTED ((uint8_t)0x04)
#define FLASH_SUSPENDED ((uint8_t)0x08)
uint32_t QSPI_W25Qx_ReadID(void);
void QSPI_W25Qx_Reset_Memory();
void QSPI_W25Qx_EraseSector(uint32_t _SectorAddr);
uint8_t QSPI_W25Qx_Write_Buffer(uint8_t *_pBuf,uint32_t _write_Addr,uint16_t _write_Size);
void QSPI_W25Qx_Read_Buffer(uint8_t *_pBuf,uint32_t _read_Addr,uint32_t _read_Size);
void QSPI_W25Qx_EraseDownLoadFlash();
void user_Assert(char *file,uint32_t line);
#endif /* BSP_QSPI_W25Q128_H_ */

14
Bingoo/include/base/bsp_slide_averager.h

@ -0,0 +1,14 @@
/*
* bsp_slide_averager.h
*
* Created on: 2026320
* Author: L1ng the codeGod
*/
#ifndef BASE_INC_BSP_BSP_SLIDE_AVERAGER_H_
#define BASE_INC_BSP_BSP_SLIDE_AVERAGER_H_
void slide_averager_init(float buffer[], uint8_t *p_index, uint8_t *p_count);
float slide_averager_calc(float buffer[], uint8_t *p_index, uint8_t *p_count, float new_data);
#endif /* BASE_INC_BSP_BSP_SLIDE_AVERAGER_H_ */

61
Bingoo/include/base/bsp_strain_gauge.pb.h

@ -0,0 +1,61 @@
/* Automatically generated nanopb header */
/* Generated by nanopb-0.4.8 */
#ifndef PB_BSP_STRAIN_GAUGE_PB_H_INCLUDED
#define PB_BSP_STRAIN_GAUGE_PB_H_INCLUDED
#include "pb.h"
#if PB_PROTO_HEADER_VERSION != 40
#error Regenerate this file with the current version of nanopb generator.
#endif
/* Struct definitions */
/* 从机地址0x32; */
typedef struct _Strain_Gauge_Struct {
int32_t MotorControl; /* 寄存器0: 电机控制,=0 停止,=1 前进,=2 后退 */
int32_t Pressure; /* 寄存器1: 输出的传感器最终数据 */
int32_t HX711_K; /* 寄存器2 HX711_K */
int32_t HX711_D; /* 寄存器3 HX711_D */
int32_t Save; /* 寄存器9: 设置为55时,把当前寄存器输入存入flash,写入成功自动变成1 */
} Strain_Gauge_Struct;
#ifdef __cplusplus
extern "C" {
#endif
/* Initializer values for message structs */
#define Strain_Gauge_Struct_init_default {0, 0, 0, 0, 0}
#define Strain_Gauge_Struct_init_zero {0, 0, 0, 0, 0}
/* Field tags (for use in manual encoding/decoding) */
#define Strain_Gauge_Struct_MotorControl_tag 1
#define Strain_Gauge_Struct_Pressure_tag 2
#define Strain_Gauge_Struct_HX711_K_tag 3
#define Strain_Gauge_Struct_HX711_D_tag 4
#define Strain_Gauge_Struct_Save_tag 5
/* Struct field encoding specification for nanopb */
#define Strain_Gauge_Struct_FIELDLIST(X, a) \
X(a, STATIC, SINGULAR, INT32, MotorControl, 1) \
X(a, STATIC, SINGULAR, INT32, Pressure, 2) \
X(a, STATIC, SINGULAR, INT32, HX711_K, 3) \
X(a, STATIC, SINGULAR, INT32, HX711_D, 4) \
X(a, STATIC, SINGULAR, INT32, Save, 5)
#define Strain_Gauge_Struct_CALLBACK NULL
#define Strain_Gauge_Struct_DEFAULT NULL
extern const pb_msgdesc_t Strain_Gauge_Struct_msg;
/* Defines for backwards compatibility with code written before nanopb-0.4.0 */
#define Strain_Gauge_Struct_fields &Strain_Gauge_Struct_msg
/* Maximum encoded size of messages (where known) */
#define BSP_STRAIN_GAUGE_PB_H_MAX_SIZE Strain_Gauge_Struct_size
#define Strain_Gauge_Struct_size 55
#ifdef __cplusplus
} /* extern "C" */
#endif
#endif

19
Bingoo/include/base/bsp_tempature.h

@ -0,0 +1,19 @@
/*
* bsp_adc.h
*
* Created on: Feb 21, 2025
* Author: akeguo
*/
#ifndef INC_BSP_BSP_TEMPATURE_H_
#define INC_BSP_BSP_TEMPATURE_H_
#include "main.h"
#include "DLTuc.h"
int32_t read_temperature();
void ADC_Intialize();
extern int32_t * tempature;
#endif /* INC_BSP_BSP_TEMPATURE_H_ */

56
Bingoo/include/base/change_line_control.h

@ -0,0 +1,56 @@
/*
* change_line_control.h
*
* Created on: 2025812
* Author: xsq
*/
#ifndef FSM_INC_CHANGE_LINE_CONTROL_H_
#define FSM_INC_CHANGE_LINE_CONTROL_H_
typedef enum _vertical_LaneChangeState
{
VerticalChange_TurnToUP,
VerticalChange_TurnToDown,
VerticalChange_TurnToLeft,
VerticalChange_TurnToRight,
VerticalChange_DelayMove,
VerticalChange_End,
VerticalChange_StateZero,
//0---6
} Lane_Vertical_ChangeState;
/**********************************************************/
typedef enum _horizontal_LaneChangeState
{
HorizontalChange_TurnToUP,
HorizontalChange_TurnToDown,
HorizontalChange_TurnToLeft,
HorizontalChange_TurnToRight,
HorizontalChange_DelayMove,
HorizontalChange_End,
HorizontalChange_StateZero,
} Lane_Horizontal_ChangeState;
/***********************************************************************/
//设置 换道距离和设置后退距离
typedef enum _laneChangeControlSTATE_t
{
Lane_Change_Stop = 0, Lane_Change_Start,
} LaneChangeControlSTATE;
/*****************************************************************************/
extern Lane_Vertical_ChangeState Current_Vertical_ChangeState;
extern LaneChangeControlSTATE VerticalLaneChangeState; /*当前换道处于开始或者结束*/
extern int LaneChangeControl_Paint();
extern void Vertical_Lane_Change_From_Left_To_Right_UP_Control();
extern void Vertical_Lane_Change_From_Left_To_Right_Down_Control();
extern void Vertical_Lane_Change_From_Right_To_Left_UP_Control();
extern void Vertical_Lane_Change_From_Right_To_Left_Down_Control();
extern int LaneChangeWaittime ;
#endif /* FSM_INC_CHANGE_LINE_CONTROL_H_ */

44
Bingoo/include/base/fsm_state.h

@ -0,0 +1,44 @@
/*
* fsm.h
*
* Created on: 2025714
* Author: akeguo
*/
#ifndef FSM_INC_FSM_STATE_H_
#define FSM_INC_FSM_STATE_H_
#include "stdint.h"
#include <stddef.h>
struct _transition_t;
typedef struct _transition_t transition_t;
//抽象类,用于派生其他类 将事件处理方法包含在基类中
typedef struct _transition_state_t
{
void (*robotEnter)(transition_t* p_transition); //执行Enter 激活标志位
void (*robotRun)(transition_t* p_transition); //执行相关动作
void (*robotExit)(transition_t* p_transition); //执行Exit
int State; //状态
}transition_state_t;
typedef struct _transition_t {
transition_state_t* p_state;
}transition_t;
extern void fsm_state_set(transition_t* p_this, transition_state_t* p_new_state);
extern void fsm_state_run(transition_t* p_this);
extern void fsm_state_init(transition_t* p_this,transition_state_t* inti_state);
#endif /* FSM_INC_FSM_STATE_H_ */

18
Bingoo/include/base/fsm_state_control.h

@ -0,0 +1,18 @@
/*
* fsm_state_control.h
*
* Created on: Jan 13, 2026
* Author: bm673
*/
#ifndef FSM_INC_FSM_STATE_CONTROL_H_
#define FSM_INC_FSM_STATE_CONTROL_H_
void Fsm_Init();
void GF_Dispatch();
void IV_control();
int AbnormalDetect();
typedef void (*ActionFunc)(void);
#endif /* FSM_INC_FSM_STATE_CONTROL_H_ */

21
Bingoo/include/base/motor.h

@ -0,0 +1,21 @@
/*
* motor.h
*
* Created on: 2026129
* Author: bm673
*/
#ifndef FSM_INC_MOTOR_H_
#define FSM_INC_MOTOR_H_
#endif /* FSM_INC_MOTOR_H_ */

Some files were not shown because too many files changed in this diff

Loading…
Cancel
Save