support restart usb port device by cdc serial port
parent
b43b2a6616
commit
b71014583e
|
@ -6,7 +6,7 @@
|
||||||
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
|
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
|
||||||
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
|
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
|
||||||
<provider copy-of="extension" id="org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser"/>
|
<provider copy-of="extension" id="org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser"/>
|
||||||
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="618447504645106327" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="1047932562834865066" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||||
<language-scope id="org.eclipse.cdt.core.gcc"/>
|
<language-scope id="org.eclipse.cdt.core.gcc"/>
|
||||||
<language-scope id="org.eclipse.cdt.core.g++"/>
|
<language-scope id="org.eclipse.cdt.core.g++"/>
|
||||||
</provider>
|
</provider>
|
||||||
|
@ -18,7 +18,7 @@
|
||||||
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
|
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
|
||||||
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
|
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
|
||||||
<provider copy-of="extension" id="org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser"/>
|
<provider copy-of="extension" id="org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser"/>
|
||||||
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="575369762763518865" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="1004854820953277604" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD "${INPUTS}"" prefer-non-shared="true">
|
||||||
<language-scope id="org.eclipse.cdt.core.gcc"/>
|
<language-scope id="org.eclipse.cdt.core.gcc"/>
|
||||||
<language-scope id="org.eclipse.cdt.core.g++"/>
|
<language-scope id="org.eclipse.cdt.core.g++"/>
|
||||||
</provider>
|
</provider>
|
||||||
|
|
|
@ -124,7 +124,7 @@ extern NaviKit_t NaviKit;
|
||||||
|
|
||||||
//device on board
|
//device on board
|
||||||
enum Device_t{USB2_Port1,USB2_Port2,USB2_Port3,USB2_Port4,USB2_Port5,USB2_Port6, //USB2.0 Port
|
enum Device_t{USB2_Port1,USB2_Port2,USB2_Port3,USB2_Port4,USB2_Port5,USB2_Port6, //USB2.0 Port
|
||||||
USB3_Port1,USB3_Port2,USB3_Port3,USB3_Port4,USB3_Port5,USB3_Port6, //USB3.0 Port
|
USB3_Port5,USB3_Port6,USB3_Port1,USB3_Port2,USB3_Port3,USB3_Port4, //USB3.0 Port
|
||||||
SOC_USB2_HUB,SOC_USB3_HUB,SOC_USB3_HOST,SOC_USB3_GEC,SOC_GE_SW, //SOC on Board
|
SOC_USB2_HUB,SOC_USB3_HUB,SOC_USB3_HOST,SOC_USB3_GEC,SOC_GE_SW, //SOC on Board
|
||||||
SYS_FAN1,SYS_FAN2,SYS_FAN3, //Fan on Board
|
SYS_FAN1,SYS_FAN2,SYS_FAN3, //Fan on Board
|
||||||
SYS_RUN_LED,SYS_PWR_LED, //LED on Board
|
SYS_RUN_LED,SYS_PWR_LED, //LED on Board
|
||||||
|
|
|
@ -36,6 +36,7 @@
|
||||||
#include "adc.h"
|
#include "adc.h"
|
||||||
#include "i2c.h"
|
#include "i2c.h"
|
||||||
#include "log.h"
|
#include "log.h"
|
||||||
|
#include "usbd_cdc_if.h"
|
||||||
/* USER CODE END Includes */
|
/* USER CODE END Includes */
|
||||||
|
|
||||||
/* Private typedef -----------------------------------------------------------*/
|
/* Private typedef -----------------------------------------------------------*/
|
||||||
|
@ -55,7 +56,8 @@
|
||||||
|
|
||||||
/* Private variables ---------------------------------------------------------*/
|
/* Private variables ---------------------------------------------------------*/
|
||||||
/* USER CODE BEGIN Variables */
|
/* USER CODE BEGIN Variables */
|
||||||
|
extern uint8_t port_restart;
|
||||||
|
extern bool flag_restart;
|
||||||
//Timer
|
//Timer
|
||||||
osTimerId_t PwrBtnLongPressTimerHandle;
|
osTimerId_t PwrBtnLongPressTimerHandle;
|
||||||
const osTimerAttr_t PwrBtnLongPressTimer_attributes = {
|
const osTimerAttr_t PwrBtnLongPressTimer_attributes = {
|
||||||
|
@ -79,6 +81,14 @@ const osTimerAttr_t IdleStateHoldTimer_attributes = {
|
||||||
};
|
};
|
||||||
|
|
||||||
//Thread
|
//Thread
|
||||||
|
|
||||||
|
osThreadId_t cdcMonitorTaskHandle;
|
||||||
|
const osThreadAttr_t cdcMonitorTask_attributes = {
|
||||||
|
.name = "cdcMonitorTask",
|
||||||
|
.priority = (osPriority_t) osPriorityNormal,
|
||||||
|
.stack_size = 128 * 4
|
||||||
|
};
|
||||||
|
|
||||||
osThreadId_t LogtoUartTaskHandle;
|
osThreadId_t LogtoUartTaskHandle;
|
||||||
const osThreadAttr_t LogtoUartTask_attributes = {
|
const osThreadAttr_t LogtoUartTask_attributes = {
|
||||||
.name = "LogtoUartTask",
|
.name = "LogtoUartTask",
|
||||||
|
@ -156,6 +166,7 @@ void IdleStateHoldTimerCallback(void *argument);
|
||||||
|
|
||||||
//task
|
//task
|
||||||
void StartLogtoUartTask(void *argument);
|
void StartLogtoUartTask(void *argument);
|
||||||
|
void StartCdcMonitorTask(void *argument);
|
||||||
|
|
||||||
void StartTestTask1(void *argument);
|
void StartTestTask1(void *argument);
|
||||||
void StartTestTask2(void *argument);
|
void StartTestTask2(void *argument);
|
||||||
|
@ -296,6 +307,8 @@ void MX_FREERTOS_Init(void) {
|
||||||
// TestTask1Handle = osThreadNew(StartTestTask1, NULL, &TestTask1_attributes);
|
// TestTask1Handle = osThreadNew(StartTestTask1, NULL, &TestTask1_attributes);
|
||||||
// TestTask2Handle = osThreadNew(StartTestTask2, NULL, &TestTask2_attributes);
|
// TestTask2Handle = osThreadNew(StartTestTask2, NULL, &TestTask2_attributes);
|
||||||
|
|
||||||
|
cdcMonitorTaskHandle = osThreadNew(StartCdcMonitorTask, NULL, &cdcMonitorTask_attributes);
|
||||||
|
|
||||||
/* USER CODE END RTOS_THREADS */
|
/* USER CODE END RTOS_THREADS */
|
||||||
|
|
||||||
/* USER CODE BEGIN RTOS_EVENTS */
|
/* USER CODE BEGIN RTOS_EVENTS */
|
||||||
|
@ -647,6 +660,19 @@ void StartEventDetect(void *argument)
|
||||||
/* Private application code --------------------------------------------------*/
|
/* Private application code --------------------------------------------------*/
|
||||||
/* USER CODE BEGIN Application */
|
/* USER CODE BEGIN Application */
|
||||||
|
|
||||||
|
void StartCdcMonitorTask(void *argument){
|
||||||
|
for(;;){
|
||||||
|
if(flag_restart && port_restart<12){
|
||||||
|
flag_restart = false;
|
||||||
|
uint8_t port_restart_temp = port_restart;
|
||||||
|
Log(info,sys,"Port%d restart",port_restart_temp);
|
||||||
|
PWR_Enable(port_restart_temp, false,400);
|
||||||
|
TaskBeep(50,1);
|
||||||
|
PWR_Enable(port_restart_temp, true,0);
|
||||||
|
}
|
||||||
|
osDelay(200);
|
||||||
|
}
|
||||||
|
}
|
||||||
void StartLogtoUartTask(void *argument){
|
void StartLogtoUartTask(void *argument){
|
||||||
|
|
||||||
// HAL_UART_Transmit(&huart1,(uint8_t *)&ch,1,2);
|
// HAL_UART_Transmit(&huart1,(uint8_t *)&ch,1,2);
|
||||||
|
@ -733,7 +759,6 @@ void IdleStateHoldTimerCallback(void *argument){
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/* USER CODE END Application */
|
/* USER CODE END Application */
|
||||||
|
|
||||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||||
|
|
|
@ -0,0 +1,72 @@
|
||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<launchConfiguration type="com.st.stm32cube.ide.mcu.debug.launch.launchConfigurationType">
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.access_port_id" value="0"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.enable_live_expr" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.enable_swv" value="false"/>
|
||||||
|
<intAttribute key="com.st.stm32cube.ide.mcu.debug.launch.formatVersion" value="2"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.ip_address_local" value="localhost"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.loadList" value="{"fItems":[{"fIsFromMainTab":true,"fPath":"Debug/NaviKit_EC_stm32.elf","fProjectName":"NaviKit_EC_stm32","fPerformBuild":true,"fDownload":true,"fLoadSymbols":true}]}"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.override_start_address_mode" value="default"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.remoteCommand" value="target remote"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startServer" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.exception.divby0" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.exception.unaligned" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.haltonexception" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swd_mode" value="true"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_port" value="61235"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_trace_div" value="8"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_trace_hclk" value="16000000"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.useRemoteTarget" value="true"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.vector_table" value=""/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.verify_flash_download" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.cti_allow_halt" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.cti_signal_halt" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_external_loader" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_logging" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_max_halt_delay" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_shared_stlink" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.external_loader" value=""/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.external_loader_init" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.frequency" value="0"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.halt_all_on_reset" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.log_file" value="E:\source\STM32CubeIDE\NaviKit_EC_stm32\Debug\st-link_gdbserver_log.txt"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.low_power_debug" value="enable"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.max_halt_delay" value="2"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.reset_strategy" value="connect_under_reset"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.stlink_check_serial_number" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.stlink_txt_serial_number" value=""/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.watchdog_config" value="none"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlinkrestart_configurations" value="{"fItems":[{"fDisplayName":"Reset","fIsSuppressible":false,"fResetAttribute":"Reset","fResetStrategies":[{"fDisplayName":"Reset","fLaunchAttribute":"monitor reset","fGdbCommands":["monitor reset"],"fCmdOptions":[]},{"fDisplayName":"None","fLaunchAttribute":"no_reset","fGdbCommands":[],"fCmdOptions":[]}],"fGdbCommandGroup":{"name":"Additional commands","commands":[]}}]}"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.swv.swv_wait_for_sync" value="true"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.doHalt" value="false"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.doReset" value="false"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.initCommands" value=""/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.ipAddress" value="localhost"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.jtagDevice" value="ST-LINK (ST-LINK GDB server)"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.pcRegister" value=""/>
|
||||||
|
<intAttribute key="org.eclipse.cdt.debug.gdbjtag.core.portNumber" value="61234"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.runCommands" value=""/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setPcRegister" value="false"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setResume" value="true"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setStopAt" value="true"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.stopAt" value="main"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.dsf.gdb.DEBUG_NAME" value="arm-none-eabi-gdb"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.dsf.gdb.NON_STOP" value="true"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.dsf.gdb.UPDATE_THREADLIST_ON_SUSPEND" value="false"/>
|
||||||
|
<intAttribute key="org.eclipse.cdt.launch.ATTR_BUILD_BEFORE_LAUNCH_ATTR" value="2"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.COREFILE_PATH" value=""/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.DEBUGGER_START_MODE" value="remote"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.launch.DEBUGGER_STOP_AT_MAIN" value="true"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.DEBUGGER_STOP_AT_MAIN_SYMBOL" value="main"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.PROGRAM_NAME" value="Debug/NaviKit_EC_stm32.elf"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_ATTR" value="NaviKit_EC_stm32"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_AUTO_ATTR" value="true"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_ID_ATTR" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.config.exe.debug.502298629"/>
|
||||||
|
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_PATHS">
|
||||||
|
<listEntry value="/NaviKit_EC_stm32"/>
|
||||||
|
</listAttribute>
|
||||||
|
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_TYPES">
|
||||||
|
<listEntry value="4"/>
|
||||||
|
</listAttribute>
|
||||||
|
<stringAttribute key="process_factory_id" value="org.eclipse.cdt.dsf.gdb.GdbProcessFactory"/>
|
||||||
|
</launchConfiguration>
|
|
@ -0,0 +1,73 @@
|
||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<launchConfiguration type="com.st.stm32cube.ide.mcu.debug.launch.launchConfigurationType">
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.access_port_id" value="0"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.enable_live_expr" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.enable_swv" value="false"/>
|
||||||
|
<intAttribute key="com.st.stm32cube.ide.mcu.debug.launch.formatVersion" value="2"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.ip_address_local" value="localhost"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.loadList" value="{"fItems":[{"fIsFromMainTab":true,"fPath":"Debug/NaviKit_stm32.elf","fProjectName":"NaviKit_EC_stm32","fPerformBuild":true,"fDownload":true,"fLoadSymbols":true}]}"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.override_start_address_mode" value="default"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.remoteCommand" value="target remote"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startServer" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.exception.divby0" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.exception.unaligned" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.haltonexception" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swd_mode" value="true"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_port" value="61235"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_trace_div" value="8"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_trace_hclk" value="16000000"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.useRemoteTarget" value="true"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.vector_table" value=""/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.verify_flash_download" value="true"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.cti_allow_halt" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.cti_signal_halt" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_external_loader" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_logging" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_max_halt_delay" value="false"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_shared_stlink" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.external_loader" value=""/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.external_loader_init" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.frequency" value="0"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.halt_all_on_reset" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.log_file" value="E:\source\STM32CubeIDE\NaviKit_EC_stm32\Debug\st-link_gdbserver_log.txt"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.low_power_debug" value="enable"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.max_halt_delay" value="2"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.reset_strategy" value="connect_under_reset"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.stlink_check_serial_number" value="false"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.stlink_txt_serial_number" value=""/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.watchdog_config" value="none"/>
|
||||||
|
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlinkrestart_configurations" value="{"fItems":[{"fDisplayName":"Reset","fIsSuppressible":false,"fResetAttribute":"Reset","fResetStrategies":[{"fDisplayName":"Reset","fLaunchAttribute":"monitor reset","fGdbCommands":["monitor reset"],"fCmdOptions":[]},{"fDisplayName":"None","fLaunchAttribute":"no_reset","fGdbCommands":[],"fCmdOptions":[]}],"fGdbCommandGroup":{"name":"Additional commands","commands":[]}}]}"/>
|
||||||
|
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.swv.swv_wait_for_sync" value="true"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.doHalt" value="false"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.doReset" value="false"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.initCommands" value=""/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.ipAddress" value="localhost"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.jtagDevice" value="ST-LINK (ST-LINK GDB server)"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.pcRegister" value=""/>
|
||||||
|
<intAttribute key="org.eclipse.cdt.debug.gdbjtag.core.portNumber" value="61234"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.runCommands" value=""/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setPcRegister" value="false"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setResume" value="true"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setStopAt" value="true"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.stopAt" value="main"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.dsf.gdb.DEBUG_NAME" value="arm-none-eabi-gdb"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.dsf.gdb.NON_STOP" value="true"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.dsf.gdb.UPDATE_THREADLIST_ON_SUSPEND" value="false"/>
|
||||||
|
<intAttribute key="org.eclipse.cdt.launch.ATTR_BUILD_BEFORE_LAUNCH_ATTR" value="2"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.COREFILE_PATH" value=""/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.DEBUGGER_START_MODE" value="remote"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.launch.DEBUGGER_STOP_AT_MAIN" value="true"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.DEBUGGER_STOP_AT_MAIN_SYMBOL" value="main"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.PROGRAM_NAME" value="Debug/NaviKit_stm32.elf"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_ATTR" value="NaviKit_EC_stm32"/>
|
||||||
|
<booleanAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_AUTO_ATTR" value="true"/>
|
||||||
|
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_ID_ATTR" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.config.exe.debug.502298629"/>
|
||||||
|
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_PATHS">
|
||||||
|
<listEntry value="/NaviKit_EC_stm32"/>
|
||||||
|
</listAttribute>
|
||||||
|
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_TYPES">
|
||||||
|
<listEntry value="4"/>
|
||||||
|
</listAttribute>
|
||||||
|
<stringAttribute key="org.eclipse.dsf.launch.MEMORY_BLOCKS" value="<?xml version="1.0" encoding="UTF-8" standalone="no"?> <memoryBlockExpressionList context="reserved-for-future-use"/> "/>
|
||||||
|
<stringAttribute key="process_factory_id" value="org.eclipse.cdt.dsf.gdb.GdbProcessFactory"/>
|
||||||
|
</launchConfiguration>
|
|
@ -3,7 +3,7 @@
|
||||||
* @Author: CK.Zh
|
* @Author: CK.Zh
|
||||||
* @Date: 2020-02-20 11:39:38
|
* @Date: 2020-02-20 11:39:38
|
||||||
* @LastEditors: CK.Zh
|
* @LastEditors: CK.Zh
|
||||||
* @LastEditTime: 2021-01-07 15:23:09
|
* @LastEditTime: 2021-02-05 18:22:00
|
||||||
-->
|
-->
|
||||||
# NaviKit_stm32
|
# NaviKit_stm32
|
||||||
PM1导航套件中电源控制板源码,STM32F107VCT6,开发环境STM32CubeIDE
|
PM1导航套件中电源控制板源码,STM32F107VCT6,开发环境STM32CubeIDE
|
||||||
|
@ -14,7 +14,7 @@
|
||||||
## 3.电源监控功能(多轨电源电压监控)
|
## 3.电源监控功能(多轨电源电压监控)
|
||||||
|
|
||||||
# 串口通信协议
|
# 串口通信协议
|
||||||
* TODO
|
* 在jetson nano系统中,找到串口ACM,发送数值(0-11),即可通过硬件重启12个usb口对应的设备
|
||||||
|
|
||||||
`STM32作为CDC Device接入到USB2.0-HUB的Downsteam 7端口下`
|
`STM32作为CDC Device接入到USB2.0-HUB的Downsteam 7端口下`
|
||||||
|
|
||||||
|
|
|
@ -23,7 +23,7 @@
|
||||||
#include "usbd_cdc_if.h"
|
#include "usbd_cdc_if.h"
|
||||||
|
|
||||||
/* USER CODE BEGIN INCLUDE */
|
/* USER CODE BEGIN INCLUDE */
|
||||||
|
#include "log.h"
|
||||||
/* USER CODE END INCLUDE */
|
/* USER CODE END INCLUDE */
|
||||||
|
|
||||||
/* Private typedef -----------------------------------------------------------*/
|
/* Private typedef -----------------------------------------------------------*/
|
||||||
|
@ -100,6 +100,8 @@ uint8_t UserTxBufferFS[APP_TX_DATA_SIZE];
|
||||||
|
|
||||||
/* USER CODE BEGIN PRIVATE_VARIABLES */
|
/* USER CODE BEGIN PRIVATE_VARIABLES */
|
||||||
|
|
||||||
|
extern uint8_t port_restart = 0;
|
||||||
|
extern bool flag_restart = false;
|
||||||
/* USER CODE END PRIVATE_VARIABLES */
|
/* USER CODE END PRIVATE_VARIABLES */
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -266,6 +268,11 @@ static int8_t CDC_Receive_FS(uint8_t* Buf, uint32_t *Len)
|
||||||
/* USER CODE BEGIN 6 */
|
/* USER CODE BEGIN 6 */
|
||||||
USBD_CDC_SetRxBuffer(&hUsbDeviceFS, &Buf[0]);
|
USBD_CDC_SetRxBuffer(&hUsbDeviceFS, &Buf[0]);
|
||||||
USBD_CDC_ReceivePacket(&hUsbDeviceFS);
|
USBD_CDC_ReceivePacket(&hUsbDeviceFS);
|
||||||
|
|
||||||
|
port_restart = Buf[0];
|
||||||
|
flag_restart = true;
|
||||||
|
|
||||||
|
Log(info,sys,"cdc receive %d",port_restart);
|
||||||
return (USBD_OK);
|
return (USBD_OK);
|
||||||
/* USER CODE END 6 */
|
/* USER CODE END 6 */
|
||||||
}
|
}
|
||||||
|
|
|
@ -31,7 +31,7 @@
|
||||||
#include "usbd_cdc.h"
|
#include "usbd_cdc.h"
|
||||||
|
|
||||||
/* USER CODE BEGIN INCLUDE */
|
/* USER CODE BEGIN INCLUDE */
|
||||||
|
#include "stdbool.h"
|
||||||
/* USER CODE END INCLUDE */
|
/* USER CODE END INCLUDE */
|
||||||
|
|
||||||
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
|
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
|
||||||
|
|
Loading…
Reference in New Issue