换电脑
This commit is contained in:
		
							parent
							
								
									318287223c
								
							
						
					
					
						commit
						a0d054f85a
					
				| @ -433,11 +433,13 @@ Mcu.Pin61=VP_OCTOSPI2_VS_quad | |||||||
| Mcu.Pin62=VP_SYS_VS_tim23 | Mcu.Pin62=VP_SYS_VS_tim23 | ||||||
| Mcu.Pin63=VP_USB_DEVICE_VS_USB_DEVICE_CDC_HS | Mcu.Pin63=VP_USB_DEVICE_VS_USB_DEVICE_CDC_HS | ||||||
| Mcu.Pin64=VP_MEMORYMAP_VS_MEMORYMAP | Mcu.Pin64=VP_MEMORYMAP_VS_MEMORYMAP | ||||||
|  | Mcu.Pin65=VP_STMicroelectronics.X-CUBE-ALGOBUILD_VS_DSPOoLibraryJjLibrary_1.4.0_1.4.0 | ||||||
| Mcu.Pin7=PC0 | Mcu.Pin7=PC0 | ||||||
| Mcu.Pin8=PC1 | Mcu.Pin8=PC1 | ||||||
| Mcu.Pin9=PC2_C | Mcu.Pin9=PC2_C | ||||||
| Mcu.PinsNb=65 | Mcu.PinsNb=66 | ||||||
| Mcu.ThirdPartyNb=0 | Mcu.ThirdParty0=STMicroelectronics.X-CUBE-ALGOBUILD.1.4.0 | ||||||
|  | Mcu.ThirdPartyNb=1 | ||||||
| Mcu.UserConstants= | Mcu.UserConstants= | ||||||
| Mcu.UserName=STM32H723VGTx | Mcu.UserName=STM32H723VGTx | ||||||
| MxCube.Version=6.14.1 | MxCube.Version=6.14.1 | ||||||
| @ -846,6 +848,10 @@ SPI2.Direction=SPI_DIRECTION_2LINES | |||||||
| SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,BaudRatePrescaler,CLKPolarity,CLKPhase | SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,BaudRatePrescaler,CLKPolarity,CLKPhase | ||||||
| SPI2.Mode=SPI_MODE_MASTER | SPI2.Mode=SPI_MODE_MASTER | ||||||
| SPI2.VirtualType=VM_MASTER | SPI2.VirtualType=VM_MASTER | ||||||
|  | STMicroelectronics.X-CUBE-ALGOBUILD.1.4.0.DSPOoLibraryJjLibrary_Checked=true | ||||||
|  | STMicroelectronics.X-CUBE-ALGOBUILD.1.4.0.IPParameters=LibraryCcDSPOoLibraryJjDSPOoLibrary | ||||||
|  | STMicroelectronics.X-CUBE-ALGOBUILD.1.4.0.LibraryCcDSPOoLibraryJjDSPOoLibrary=true | ||||||
|  | STMicroelectronics.X-CUBE-ALGOBUILD.1.4.0_SwParameter=LibraryCcDSPOoLibraryJjDSPOoLibrary\:true; | ||||||
| TIM1.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1 | TIM1.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1 | ||||||
| TIM1.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3 | TIM1.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3 | ||||||
| TIM1.IPParameters=Channel-PWM Generation3 CH3,Channel-PWM Generation1 CH1,Period,Pulse-PWM Generation1 CH1,Pulse-PWM Generation3 CH3,Prescaler | TIM1.IPParameters=Channel-PWM Generation3 CH3,Channel-PWM Generation1 CH1,Period,Pulse-PWM Generation1 CH1,Pulse-PWM Generation3 CH3,Prescaler | ||||||
| @ -908,6 +914,8 @@ VP_MEMORYMAP_VS_MEMORYMAP.Mode=CurAppReg | |||||||
| VP_MEMORYMAP_VS_MEMORYMAP.Signal=MEMORYMAP_VS_MEMORYMAP | VP_MEMORYMAP_VS_MEMORYMAP.Signal=MEMORYMAP_VS_MEMORYMAP | ||||||
| VP_OCTOSPI2_VS_quad.Mode=quad_mode | VP_OCTOSPI2_VS_quad.Mode=quad_mode | ||||||
| VP_OCTOSPI2_VS_quad.Signal=OCTOSPI2_VS_quad | VP_OCTOSPI2_VS_quad.Signal=OCTOSPI2_VS_quad | ||||||
|  | VP_STMicroelectronics.X-CUBE-ALGOBUILD_VS_DSPOoLibraryJjLibrary_1.4.0_1.4.0.Mode=DSPOoLibraryJjLibrary | ||||||
|  | VP_STMicroelectronics.X-CUBE-ALGOBUILD_VS_DSPOoLibraryJjLibrary_1.4.0_1.4.0.Signal=STMicroelectronics.X-CUBE-ALGOBUILD_VS_DSPOoLibraryJjLibrary_1.4.0_1.4.0 | ||||||
| VP_SYS_VS_tim23.Mode=TIM23 | VP_SYS_VS_tim23.Mode=TIM23 | ||||||
| VP_SYS_VS_tim23.Signal=SYS_VS_tim23 | VP_SYS_VS_tim23.Signal=SYS_VS_tim23 | ||||||
| VP_USB_DEVICE_VS_USB_DEVICE_CDC_HS.Mode=CDC_HS | VP_USB_DEVICE_VS_USB_DEVICE_CDC_HS.Mode=CDC_HS | ||||||
|  | |||||||
| @ -175,6 +175,16 @@ | |||||||
|           <WinNumber>1</WinNumber> |           <WinNumber>1</WinNumber> | ||||||
|           <ItemText>n100_cali</ItemText> |           <ItemText>n100_cali</ItemText> | ||||||
|         </Ww> |         </Ww> | ||||||
|  |         <Ww> | ||||||
|  |           <count>4</count> | ||||||
|  |           <WinNumber>1</WinNumber> | ||||||
|  |           <ItemText>n100</ItemText> | ||||||
|  |         </Ww> | ||||||
|  |         <Ww> | ||||||
|  |           <count>5</count> | ||||||
|  |           <WinNumber>1</WinNumber> | ||||||
|  |           <ItemText>cmd</ItemText> | ||||||
|  |         </Ww> | ||||||
|       </WatchWindow1> |       </WatchWindow1> | ||||||
|       <Tracepoint> |       <Tracepoint> | ||||||
|         <THDelay>0</THDelay> |         <THDelay>0</THDelay> | ||||||
|  | |||||||
										
											Binary file not shown.
										
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										8970
									
								
								Middlewares/ST/ARM/DSP/Inc/arm_math.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										8970
									
								
								Middlewares/ST/ARM/DSP/Inc/arm_math.h
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										201
									
								
								Middlewares/Third_Party/ARM/DSP/LICENSE.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										201
									
								
								Middlewares/Third_Party/ARM/DSP/LICENSE.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -0,0 +1,201 @@ | |||||||
|  |                                  Apache License | ||||||
|  |                            Version 2.0, January 2004 | ||||||
|  |                         http://www.apache.org/licenses/ | ||||||
|  | 
 | ||||||
|  |    TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION | ||||||
|  | 
 | ||||||
|  |    1. Definitions. | ||||||
|  | 
 | ||||||
|  |       "License" shall mean the terms and conditions for use, reproduction, | ||||||
|  |       and distribution as defined by Sections 1 through 9 of this document. | ||||||
|  | 
 | ||||||
|  |       "Licensor" shall mean the copyright owner or entity authorized by | ||||||
|  |       the copyright owner that is granting the License. | ||||||
|  | 
 | ||||||
|  |       "Legal Entity" shall mean the union of the acting entity and all | ||||||
|  |       other entities that control, are controlled by, or are under common | ||||||
|  |       control with that entity. For the purposes of this definition, | ||||||
|  |       "control" means (i) the power, direct or indirect, to cause the | ||||||
|  |       direction or management of such entity, whether by contract or | ||||||
|  |       otherwise, or (ii) ownership of fifty percent (50%) or more of the | ||||||
|  |       outstanding shares, or (iii) beneficial ownership of such entity. | ||||||
|  | 
 | ||||||
|  |       "You" (or "Your") shall mean an individual or Legal Entity | ||||||
|  |       exercising permissions granted by this License. | ||||||
|  | 
 | ||||||
|  |       "Source" form shall mean the preferred form for making modifications, | ||||||
|  |       including but not limited to software source code, documentation | ||||||
|  |       source, and configuration files. | ||||||
|  | 
 | ||||||
|  |       "Object" form shall mean any form resulting from mechanical | ||||||
|  |       transformation or translation of a Source form, including but | ||||||
|  |       not limited to compiled object code, generated documentation, | ||||||
|  |       and conversions to other media types. | ||||||
|  | 
 | ||||||
|  |       "Work" shall mean the work of authorship, whether in Source or | ||||||
|  |       Object form, made available under the License, as indicated by a | ||||||
|  |       copyright notice that is included in or attached to the work | ||||||
|  |       (an example is provided in the Appendix below). | ||||||
|  | 
 | ||||||
|  |       "Derivative Works" shall mean any work, whether in Source or Object | ||||||
|  |       form, that is based on (or derived from) the Work and for which the | ||||||
|  |       editorial revisions, annotations, elaborations, or other modifications | ||||||
|  |       represent, as a whole, an original work of authorship. For the purposes | ||||||
|  |       of this License, Derivative Works shall not include works that remain | ||||||
|  |       separable from, or merely link (or bind by name) to the interfaces of, | ||||||
|  |       the Work and Derivative Works thereof. | ||||||
|  | 
 | ||||||
|  |       "Contribution" shall mean any work of authorship, including | ||||||
|  |       the original version of the Work and any modifications or additions | ||||||
|  |       to that Work or Derivative Works thereof, that is intentionally | ||||||
|  |       submitted to Licensor for inclusion in the Work by the copyright owner | ||||||
|  |       or by an individual or Legal Entity authorized to submit on behalf of | ||||||
|  |       the copyright owner. For the purposes of this definition, "submitted" | ||||||
|  |       means any form of electronic, verbal, or written communication sent | ||||||
|  |       to the Licensor or its representatives, including but not limited to | ||||||
|  |       communication on electronic mailing lists, source code control systems, | ||||||
|  |       and issue tracking systems that are managed by, or on behalf of, the | ||||||
|  |       Licensor for the purpose of discussing and improving the Work, but | ||||||
|  |       excluding communication that is conspicuously marked or otherwise | ||||||
|  |       designated in writing by the copyright owner as "Not a Contribution." | ||||||
|  | 
 | ||||||
|  |       "Contributor" shall mean Licensor and any individual or Legal Entity | ||||||
|  |       on behalf of whom a Contribution has been received by Licensor and | ||||||
|  |       subsequently incorporated within the Work. | ||||||
|  | 
 | ||||||
|  |    2. Grant of Copyright License. Subject to the terms and conditions of | ||||||
|  |       this License, each Contributor hereby grants to You a perpetual, | ||||||
|  |       worldwide, non-exclusive, no-charge, royalty-free, irrevocable | ||||||
|  |       copyright license to reproduce, prepare Derivative Works of, | ||||||
|  |       publicly display, publicly perform, sublicense, and distribute the | ||||||
|  |       Work and such Derivative Works in Source or Object form. | ||||||
|  | 
 | ||||||
|  |    3. Grant of Patent License. Subject to the terms and conditions of | ||||||
|  |       this License, each Contributor hereby grants to You a perpetual, | ||||||
|  |       worldwide, non-exclusive, no-charge, royalty-free, irrevocable | ||||||
|  |       (except as stated in this section) patent license to make, have made, | ||||||
|  |       use, offer to sell, sell, import, and otherwise transfer the Work, | ||||||
|  |       where such license applies only to those patent claims licensable | ||||||
|  |       by such Contributor that are necessarily infringed by their | ||||||
|  |       Contribution(s) alone or by combination of their Contribution(s) | ||||||
|  |       with the Work to which such Contribution(s) was submitted. If You | ||||||
|  |       institute patent litigation against any entity (including a | ||||||
|  |       cross-claim or counterclaim in a lawsuit) alleging that the Work | ||||||
|  |       or a Contribution incorporated within the Work constitutes direct | ||||||
|  |       or contributory patent infringement, then any patent licenses | ||||||
|  |       granted to You under this License for that Work shall terminate | ||||||
|  |       as of the date such litigation is filed. | ||||||
|  | 
 | ||||||
|  |    4. Redistribution. You may reproduce and distribute copies of the | ||||||
|  |       Work or Derivative Works thereof in any medium, with or without | ||||||
|  |       modifications, and in Source or Object form, provided that You | ||||||
|  |       meet the following conditions: | ||||||
|  | 
 | ||||||
|  |       (a) You must give any other recipients of the Work or | ||||||
|  |           Derivative Works a copy of this License; and | ||||||
|  | 
 | ||||||
|  |       (b) You must cause any modified files to carry prominent notices | ||||||
|  |           stating that You changed the files; and | ||||||
|  | 
 | ||||||
|  |       (c) You must retain, in the Source form of any Derivative Works | ||||||
|  |           that You distribute, all copyright, patent, trademark, and | ||||||
|  |           attribution notices from the Source form of the Work, | ||||||
|  |           excluding those notices that do not pertain to any part of | ||||||
|  |           the Derivative Works; and | ||||||
|  | 
 | ||||||
|  |       (d) If the Work includes a "NOTICE" text file as part of its | ||||||
|  |           distribution, then any Derivative Works that You distribute must | ||||||
|  |           include a readable copy of the attribution notices contained | ||||||
|  |           within such NOTICE file, excluding those notices that do not | ||||||
|  |           pertain to any part of the Derivative Works, in at least one | ||||||
|  |           of the following places: within a NOTICE text file distributed | ||||||
|  |           as part of the Derivative Works; within the Source form or | ||||||
|  |           documentation, if provided along with the Derivative Works; or, | ||||||
|  |           within a display generated by the Derivative Works, if and | ||||||
|  |           wherever such third-party notices normally appear. The contents | ||||||
|  |           of the NOTICE file are for informational purposes only and | ||||||
|  |           do not modify the License. You may add Your own attribution | ||||||
|  |           notices within Derivative Works that You distribute, alongside | ||||||
|  |           or as an addendum to the NOTICE text from the Work, provided | ||||||
|  |           that such additional attribution notices cannot be construed | ||||||
|  |           as modifying the License. | ||||||
|  | 
 | ||||||
|  |       You may add Your own copyright statement to Your modifications and | ||||||
|  |       may provide additional or different license terms and conditions | ||||||
|  |       for use, reproduction, or distribution of Your modifications, or | ||||||
|  |       for any such Derivative Works as a whole, provided Your use, | ||||||
|  |       reproduction, and distribution of the Work otherwise complies with | ||||||
|  |       the conditions stated in this License. | ||||||
|  | 
 | ||||||
|  |    5. Submission of Contributions. Unless You explicitly state otherwise, | ||||||
|  |       any Contribution intentionally submitted for inclusion in the Work | ||||||
|  |       by You to the Licensor shall be under the terms and conditions of | ||||||
|  |       this License, without any additional terms or conditions. | ||||||
|  |       Notwithstanding the above, nothing herein shall supersede or modify | ||||||
|  |       the terms of any separate license agreement you may have executed | ||||||
|  |       with Licensor regarding such Contributions. | ||||||
|  | 
 | ||||||
|  |    6. Trademarks. This License does not grant permission to use the trade | ||||||
|  |       names, trademarks, service marks, or product names of the Licensor, | ||||||
|  |       except as required for reasonable and customary use in describing the | ||||||
|  |       origin of the Work and reproducing the content of the NOTICE file. | ||||||
|  | 
 | ||||||
|  |    7. Disclaimer of Warranty. Unless required by applicable law or | ||||||
|  |       agreed to in writing, Licensor provides the Work (and each | ||||||
|  |       Contributor provides its Contributions) on an "AS IS" BASIS, | ||||||
|  |       WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or | ||||||
|  |       implied, including, without limitation, any warranties or conditions | ||||||
|  |       of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A | ||||||
|  |       PARTICULAR PURPOSE. You are solely responsible for determining the | ||||||
|  |       appropriateness of using or redistributing the Work and assume any | ||||||
|  |       risks associated with Your exercise of permissions under this License. | ||||||
|  | 
 | ||||||
|  |    8. Limitation of Liability. In no event and under no legal theory, | ||||||
|  |       whether in tort (including negligence), contract, or otherwise, | ||||||
|  |       unless required by applicable law (such as deliberate and grossly | ||||||
|  |       negligent acts) or agreed to in writing, shall any Contributor be | ||||||
|  |       liable to You for damages, including any direct, indirect, special, | ||||||
|  |       incidental, or consequential damages of any character arising as a | ||||||
|  |       result of this License or out of the use or inability to use the | ||||||
|  |       Work (including but not limited to damages for loss of goodwill, | ||||||
|  |       work stoppage, computer failure or malfunction, or any and all | ||||||
|  |       other commercial damages or losses), even if such Contributor | ||||||
|  |       has been advised of the possibility of such damages. | ||||||
|  | 
 | ||||||
|  |    9. Accepting Warranty or Additional Liability. While redistributing | ||||||
|  |       the Work or Derivative Works thereof, You may choose to offer, | ||||||
|  |       and charge a fee for, acceptance of support, warranty, indemnity, | ||||||
|  |       or other liability obligations and/or rights consistent with this | ||||||
|  |       License. However, in accepting such obligations, You may act only | ||||||
|  |       on Your own behalf and on Your sole responsibility, not on behalf | ||||||
|  |       of any other Contributor, and only if You agree to indemnify, | ||||||
|  |       defend, and hold each Contributor harmless for any liability | ||||||
|  |       incurred by, or claims asserted against, such Contributor by reason | ||||||
|  |       of your accepting any such warranty or additional liability. | ||||||
|  | 
 | ||||||
|  |    END OF TERMS AND CONDITIONS | ||||||
|  | 
 | ||||||
|  |    APPENDIX: How to apply the Apache License to your work. | ||||||
|  | 
 | ||||||
|  |       To apply the Apache License to your work, attach the following | ||||||
|  |       boilerplate notice, with the fields enclosed by brackets "{}" | ||||||
|  |       replaced with your own identifying information. (Don't include | ||||||
|  |       the brackets!)  The text should be enclosed in the appropriate | ||||||
|  |       comment syntax for the file format. We also recommend that a | ||||||
|  |       file or class name and description of purpose be included on the | ||||||
|  |       same "printed page" as the copyright notice for easier | ||||||
|  |       identification within third-party archives. | ||||||
|  | 
 | ||||||
|  |    Copyright {yyyy} {name of copyright owner} | ||||||
|  | 
 | ||||||
|  |    Licensed under the Apache License, Version 2.0 (the "License"); | ||||||
|  |    you may not use this file except in compliance with the License. | ||||||
|  |    You may obtain a copy of the License at | ||||||
|  | 
 | ||||||
|  |        http://www.apache.org/licenses/LICENSE-2.0 | ||||||
|  | 
 | ||||||
|  |    Unless required by applicable law or agreed to in writing, software | ||||||
|  |    distributed under the License is distributed on an "AS IS" BASIS, | ||||||
|  |    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||||||
|  |    See the License for the specific language governing permissions and | ||||||
|  |    limitations under the License. | ||||||
| @ -19,36 +19,39 @@ static void CMD_RcLogic(const CMD_RC_t *rc, CMD_t *cmd, float dt_sec) { | |||||||
|   switch (rc->sw_l) { |   switch (rc->sw_l) { | ||||||
|       /* 左拨杆相应行为选择和解析 */ |       /* 左拨杆相应行为选择和解析 */ | ||||||
|     case CMD_SW_UP: |     case CMD_SW_UP: | ||||||
|       cmd->chassis.mode = CHASSIS_MODE_RELAX; |  | ||||||
|       switch (rc->sw_r) { |       switch (rc->sw_r) { | ||||||
|       /* 右拨杆相应行为选择和解析*/  |       /* 右拨杆相应行为选择和解析*/  | ||||||
|       case CMD_SW_UP: |       case CMD_SW_UP: | ||||||
|  |         cmd->chassis.mode = CHASSIS_MODE_RELAX; | ||||||
|         cmd->chassis.action = CHASSIS_ACTION_NONE; |         cmd->chassis.action = CHASSIS_ACTION_NONE; | ||||||
|         break; |         break; | ||||||
|       case CMD_SW_MID: |       case CMD_SW_MID: | ||||||
|  |         cmd->chassis.mode = CHASSIS_MODE_DAMP; | ||||||
|         cmd->chassis.action = CHASSIS_ACTION_NONE; |         cmd->chassis.action = CHASSIS_ACTION_NONE; | ||||||
|         break; |         break; | ||||||
|       case CMD_SW_DOWN: |       case CMD_SW_DOWN: | ||||||
|  |         cmd->chassis.mode = CHASSIS_MODE_DAMP; | ||||||
|         cmd->chassis.action = CHASSIS_ACTION_NONE; |         cmd->chassis.action = CHASSIS_ACTION_NONE; | ||||||
|         break; |         break; | ||||||
|       case CMD_SW_ERR: |       case CMD_SW_ERR: | ||||||
|  |         cmd->chassis.mode = CHASSIS_MODE_RELAX; | ||||||
|         cmd->chassis.action = CHASSIS_ACTION_NONE; |         cmd->chassis.action = CHASSIS_ACTION_NONE; | ||||||
|         break; |         break; | ||||||
|       } |       } | ||||||
|       break; |       break; | ||||||
| 
 | 
 | ||||||
|     case CMD_SW_MID: |     case CMD_SW_MID: | ||||||
|       cmd->chassis.mode = CHASSIS_MODE_DAMP; |       cmd->chassis.mode = CHASSIS_MODE_JUMP; | ||||||
|       switch (rc->sw_r) { |       switch (rc->sw_r) { | ||||||
|       /* 右拨杆相应行为选择和解析*/  |       /* 右拨杆相应行为选择和解析*/  | ||||||
|       case CMD_SW_UP: |       case CMD_SW_UP: | ||||||
|         cmd->chassis.action = CHASSIS_ACTION_NONE; |         cmd->chassis.action = CHASSIS_ACTION_STAND; | ||||||
|         break; |         break; | ||||||
|       case CMD_SW_MID: |       case CMD_SW_MID: | ||||||
|         cmd->chassis.action = CHASSIS_ACTION_NONE; |         cmd->chassis.action = CHASSIS_ACTION_WAIT_JUMP; | ||||||
|         break; |         break; | ||||||
|       case CMD_SW_DOWN: |       case CMD_SW_DOWN: | ||||||
|         cmd->chassis.action = CHASSIS_ACTION_NONE; |         cmd->chassis.action = CHASSIS_ACTION_JUMP; | ||||||
|         break; |         break; | ||||||
|       case CMD_SW_ERR: |       case CMD_SW_ERR: | ||||||
|         cmd->chassis.action = CHASSIS_ACTION_NONE; |         cmd->chassis.action = CHASSIS_ACTION_NONE; | ||||||
| @ -67,7 +70,7 @@ static void CMD_RcLogic(const CMD_RC_t *rc, CMD_t *cmd, float dt_sec) { | |||||||
|         cmd->chassis.action = CHASSIS_ACTION_STAND; |         cmd->chassis.action = CHASSIS_ACTION_STAND; | ||||||
|         break; |         break; | ||||||
|       case CMD_SW_DOWN: |       case CMD_SW_DOWN: | ||||||
|         cmd->chassis.action = CHASSIS_ACTION_TROT; |         cmd->chassis.action = CHASSIS_ACTION_SLOW_TROT; | ||||||
|         break; |         break; | ||||||
|       case CMD_SW_ERR: |       case CMD_SW_ERR: | ||||||
|         cmd->chassis.action = CHASSIS_ACTION_NONE; |         cmd->chassis.action = CHASSIS_ACTION_NONE; | ||||||
|  | |||||||
| @ -20,6 +20,7 @@ typedef enum { | |||||||
|   CHASSIS_MODE_BREAK, /* 刹车模式,电机闭环控制保持静止。用于机器人停止状态 */ |   CHASSIS_MODE_BREAK, /* 刹车模式,电机闭环控制保持静止。用于机器人停止状态 */ | ||||||
|   CHASSIS_MODE_POSITION, /* 位置模式,电机闭环控制保持在指定位置 */ |   CHASSIS_MODE_POSITION, /* 位置模式,电机闭环控制保持在指定位置 */ | ||||||
|   CHASSIS_MODE_FOLLOW, /* 通过闭环控制使车头方向跟随遥控器 */ |   CHASSIS_MODE_FOLLOW, /* 通过闭环控制使车头方向跟随遥控器 */ | ||||||
|  |   CHASSIS_MODE_JUMP, /*跳跃模式*/ | ||||||
| } CMD_ChassisMode_t; | } CMD_ChassisMode_t; | ||||||
| 
 | 
 | ||||||
| typedef enum { | typedef enum { | ||||||
| @ -27,6 +28,9 @@ typedef enum { | |||||||
|   CHASSIS_ACTION_STAND, /* 站立动作 */ |   CHASSIS_ACTION_STAND, /* 站立动作 */ | ||||||
|   CHASSIS_ACTION_WALK, /* 行走动作 */ |   CHASSIS_ACTION_WALK, /* 行走动作 */ | ||||||
|   CHASSIS_ACTION_TROT, /* 小跑动作 */ |   CHASSIS_ACTION_TROT, /* 小跑动作 */ | ||||||
|  |   CHASSIS_ACTION_SLOW_TROT, | ||||||
|  |   CHASSIS_ACTION_WAIT_JUMP, | ||||||
|  |    | ||||||
|   CHASSIS_ACTION_JUMP, /* 跳跃动作 */ |   CHASSIS_ACTION_JUMP, /* 跳跃动作 */ | ||||||
|   CHASSIS_ACTION_RUN, |   CHASSIS_ACTION_RUN, | ||||||
|   CHASSIS_ACTION_NUM, |   CHASSIS_ACTION_NUM, | ||||||
|  | |||||||
| @ -44,8 +44,8 @@ static Kinematics_JointCMD_t position_mode = { | |||||||
|     .T = 0.0f, /* 零力矩 */ |     .T = 0.0f, /* 零力矩 */ | ||||||
|     .W = 0.0f, /* 零速度 */ |     .W = 0.0f, /* 零速度 */ | ||||||
|     .Pos = 0.0f, /* 零位置 */ |     .Pos = 0.0f, /* 零位置 */ | ||||||
|     .K_P = 1.2f, /* 刚度系数 */ |     .K_P = 2.2f, /* 刚度系数 */ | ||||||
|     .K_W = 0.05f, /* 速度系数 */ |     .K_W = 0.08f, /* 速度系数 */ | ||||||
| }; | }; | ||||||
| 
 | 
 | ||||||
| // static uint8_t chassis_mode_states = 0;
 | // static uint8_t chassis_mode_states = 0;
 | ||||||
|  | |||||||
| @ -41,18 +41,18 @@ typedef enum { | |||||||
| typedef union { | typedef union { | ||||||
|   float id[GO_MOTOR_NUM]; |   float id[GO_MOTOR_NUM]; | ||||||
|   struct{ |   struct{ | ||||||
|     float lf_hip;   /* 左前腿髋关节长度,单位:米 */ |     float lf_hip; | ||||||
|     float lf_thigh; /* 左前腿大腿长度,单位:米 */ |     float lf_thigh; | ||||||
|     float lf_calf;  /* 左前腿小腿长度,单位:米 */ |     float lf_calf; | ||||||
|     float rf_hip;   /* 右前腿髋关节长度,单位:米 */ |     float rf_hip; | ||||||
|     float rf_thigh; /* 右前腿大腿长度,单位:米 */ |     float rf_thigh; | ||||||
|     float rf_calf;  /* 右前腿小腿长度,单位:米 */ |     float rf_calf; | ||||||
|     float lr_hip;   /* 左后腿髋关节长度,单位:米 */ |     float lr_hip; | ||||||
|     float lr_thigh; /* 左后腿大腿长度,单位:米 */ |     float lr_thigh; | ||||||
|     float lr_calf;  /* 左后腿小腿长度,单位:米 */ |     float lr_calf; | ||||||
|     float rr_hip;   /* 右后腿髋关节长度,单位:米 */ |     float rr_hip; | ||||||
|     float rr_thigh; /* 右后腿大腿长度,单位:米 */ |     float rr_thigh; | ||||||
|     float rr_calf;  /* 右后腿小腿长度,单位:米 */ |     float rr_calf; | ||||||
|   } named; |   } named; | ||||||
| } joint_params; | } joint_params; | ||||||
| 
 | 
 | ||||||
| @ -61,6 +61,20 @@ typedef struct { | |||||||
|   float y; |   float y; | ||||||
|   float z; |   float z; | ||||||
| } joint_pos; | } joint_pos; | ||||||
|  | 
 | ||||||
|  | typedef struct { | ||||||
|  |   float x; | ||||||
|  |   float y; | ||||||
|  |   float z; | ||||||
|  | } foot_pos; | ||||||
|  | 
 | ||||||
|  | typedef struct { | ||||||
|  |   foot_pos lf; | ||||||
|  |   foot_pos rf; | ||||||
|  |   foot_pos lr; | ||||||
|  |   foot_pos rr; | ||||||
|  | } foots_pos; | ||||||
|  | 
 | ||||||
| typedef struct { | typedef struct { | ||||||
|   joint_params min; |   joint_params min; | ||||||
|   joint_params max; |   joint_params max; | ||||||
| @ -80,8 +94,6 @@ typedef union { | |||||||
| typedef struct{ | typedef struct{ | ||||||
|   joint_params zero_point; /* 零点角度,单位:弧度 */ |   joint_params zero_point; /* 零点角度,单位:弧度 */ | ||||||
| 
 | 
 | ||||||
|   // joint_params length;     /* 关节长度,单位:米 */
 |  | ||||||
|   |  | ||||||
|   joint_params ratio;      /* 关节减速比 */ |   joint_params ratio;      /* 关节减速比 */ | ||||||
|   joint_limits limit; /* 关节的最小和最大角度,单位:弧度 */ |   joint_limits limit; /* 关节的最小和最大角度,单位:弧度 */ | ||||||
|    |    | ||||||
| @ -99,6 +111,7 @@ typedef struct { | |||||||
| 
 | 
 | ||||||
|   KPID_Params_t torque_pid_param; /* 力矩矩控制PID的参数 */ |   KPID_Params_t torque_pid_param; /* 力矩矩控制PID的参数 */ | ||||||
|   KPID_Params_t blance_pid_param; /* 平衡PID的参数 */ |   KPID_Params_t blance_pid_param; /* 平衡PID的参数 */ | ||||||
|  | 
 | ||||||
|   /* 低通滤波器截止频率 */ |   /* 低通滤波器截止频率 */ | ||||||
|   struct { |   struct { | ||||||
|     float in;  /* 输入 */ |     float in;  /* 输入 */ | ||||||
| @ -113,11 +126,11 @@ typedef struct { | |||||||
|  */ |  */ | ||||||
| typedef struct { | typedef struct { | ||||||
|   uint32_t lask_wakeup; |   uint32_t lask_wakeup; | ||||||
|  | 
 | ||||||
|   float dt; |   float dt; | ||||||
|   float time; |   float time; | ||||||
| 
 | 
 | ||||||
|   const Chassis_Params_t *param; /* 底盘的参数,用Chassis_Init设定 */ |   const Chassis_Params_t *param; /* 底盘的参数,用Chassis_Init设定 */ | ||||||
| 
 |  | ||||||
|   GO_ChassisFeedback_t feedback; /* 底盘反馈信息 */ |   GO_ChassisFeedback_t feedback; /* 底盘反馈信息 */ | ||||||
|   GO_ChassisCMD_t output; |   GO_ChassisCMD_t output; | ||||||
|   float height; /* 底盘高度,单位:米 */ |   float height; /* 底盘高度,单位:米 */ | ||||||
| @ -143,14 +156,18 @@ typedef struct { | |||||||
|     }end_pos;   |     }end_pos;   | ||||||
|   } leg_pos; /* 四条腿的关节位置,单位:米 */ |   } leg_pos; /* 四条腿的关节位置,单位:米 */ | ||||||
| 
 | 
 | ||||||
|  |   struct { | ||||||
|  |     foots_pos *leg; | ||||||
|  |   } foots; /* 四条腿的足端位置*/ | ||||||
|  | 
 | ||||||
|   /* 模块通用 */ |   /* 模块通用 */ | ||||||
|   CMD_ChassisMode_t mode; /* 底盘模式 */ |   CMD_ChassisMode_t mode; /* 底盘模式 */ | ||||||
|    |    | ||||||
|   CMD_ChassisAction_t action; /* 底盘模式 */ |   CMD_ChassisAction_t action; /* 底盘模式 */ | ||||||
| 
 | 
 | ||||||
|   AHRS_Eulr_t eulr_imu; /* 欧拉角,单位:弧度 */ |   AHRS_Eulr_t eulr_imu; /* IMU获取的欧拉角 */ | ||||||
| 
 | 
 | ||||||
|   AHRS_Eulr_t delta_eulr; /* 欧拉角变化量,单位:弧度 */ |   AHRS_Eulr_t delta_eulr; /* 欧拉角变化量 */ | ||||||
| 
 | 
 | ||||||
|   AHRS_Eulr_t eulr_setpoint; /* 期望的欧拉角,单位:弧度 */ |   AHRS_Eulr_t eulr_setpoint; /* 期望的欧拉角,单位:弧度 */ | ||||||
|    |    | ||||||
|  | |||||||
| @ -11,7 +11,7 @@ | |||||||
| 
 | 
 | ||||||
| #define CONFIG_BASE_ADDRESS (ADDR_FLASH_SECTOR_11) | #define CONFIG_BASE_ADDRESS (ADDR_FLASH_SECTOR_11) | ||||||
| 
 | 
 | ||||||
| #define JOINT_CALF_OFFSET (2.7321f * 12.66) | #define JOINT_CALF_OFFSET (2.7321f * 12.66f) | ||||||
| 
 | 
 | ||||||
| Config_t param_default = { | Config_t param_default = { | ||||||
| 
 | 
 | ||||||
| @ -19,7 +19,9 @@ Config_t param_default = { | |||||||
|         .left_leg = BSP_UART_LEFT_LEG, |         .left_leg = BSP_UART_LEFT_LEG, | ||||||
|         .right_leg = BSP_UART_RIGHT_LEG, |         .right_leg = BSP_UART_RIGHT_LEG, | ||||||
|     }, |     }, | ||||||
|  | 
 | ||||||
|     .chassis_imu_type = IMU_WHEELREC_N100, |     .chassis_imu_type = IMU_WHEELREC_N100, | ||||||
|  | 
 | ||||||
|     .cali = { |     .cali = { | ||||||
|         .bmi088 = { |         .bmi088 = { | ||||||
|             .gyro_offset = {0.0f, 0.0f, 0.0f}, |             .gyro_offset = {0.0f, 0.0f, 0.0f}, | ||||||
| @ -30,25 +32,25 @@ Config_t param_default = { | |||||||
|         .type = CHASSIS_TYPE_QUADRUPED, |         .type = CHASSIS_TYPE_QUADRUPED, | ||||||
| 
 | 
 | ||||||
|         .torque_pid_param = { |         .torque_pid_param = { | ||||||
|             .k = 5.0f, /* 控制器增益 */ |             .k = 5.0f, | ||||||
|             .p = 20.0f, /* 比例项增益 */ |             .p = 20.0f, | ||||||
|             .i = 1.0f, /* 积分项增益 */ |             .i = 1.0f, | ||||||
|             .d = 0.0f, /* 微分项增益 */ |             .d = 0.0f, | ||||||
|             .i_limit = 100.0f, /* 积分项上限 */ |             .i_limit = 100.0f, | ||||||
|             .out_limit = 100.0f, /* 输出绝对值限制 */ |             .out_limit = 100.0f, | ||||||
|             .d_cutoff_freq = -1.0f, /* D项低通截止频率 */ |             .d_cutoff_freq = -1.0f, | ||||||
|             .range = -1.0f, /* 计算循环误差时使用,大于0时启用 */ |             .range = -1.0f, | ||||||
|         }, |         }, | ||||||
| 
 | 
 | ||||||
|         .blance_pid_param = { |         .blance_pid_param = { | ||||||
|             .k = 1.00f, /* 控制器增益 */ |             .k = 1.00f, | ||||||
|             .p = 0.08f, /* 比例项增益 */ |             .p = 0.08f, | ||||||
|             .i = 0.08f, /* 积分项增益 */ |             .i = 0.08f, | ||||||
|             .d = 0.0f, /* 微分项增益 */ |             .d = 0.0f, | ||||||
|             .i_limit = 0.05f, /* 积分项上限 */ |             .i_limit = 0.05f, | ||||||
|             .out_limit = 0.1f, /* 输出绝对值限制 */ |             .out_limit = 0.1f, | ||||||
|             .d_cutoff_freq = -1.0f, /* D项低通截止频率 */ |             .d_cutoff_freq = -1.0f, | ||||||
|             .range = -1.0f, /* 计算循环误差时使用,大于0时启用 */ |             .range = -1.0f, | ||||||
|         }, |         }, | ||||||
|          |          | ||||||
|         .low_pass_cutoff_freq = { |         .low_pass_cutoff_freq = { | ||||||
| @ -57,11 +59,13 @@ Config_t param_default = { | |||||||
|         }, |         }, | ||||||
| 
 | 
 | ||||||
|         .mech_param = { |         .mech_param = { | ||||||
|  |              | ||||||
|             .length = { |             .length = { | ||||||
|                 .hip = 0.0861f, |                 .hip = 0.0861f, | ||||||
|                 .thigh = 0.20f, |                 .thigh = 0.20f, | ||||||
|                 .calf = 0.20f,  |                 .calf = 0.20f,  | ||||||
|             }, |             }, | ||||||
|  | 
 | ||||||
|             .limit = { |             .limit = { | ||||||
|                 .max = { |                 .max = { | ||||||
|                     .named = { |                     .named = { | ||||||
| @ -79,6 +83,7 @@ Config_t param_default = { | |||||||
|                         .rr_calf = -1.2f,  /* 右后腿小腿最大角度,单位:弧度 */ |                         .rr_calf = -1.2f,  /* 右后腿小腿最大角度,单位:弧度 */ | ||||||
|                     } |                     } | ||||||
|                 }, |                 }, | ||||||
|  | 
 | ||||||
|                 .min = { |                 .min = { | ||||||
|                     .named = { |                     .named = { | ||||||
|                         .lf_hip = -0.50f,   /* 左前腿髋关节最大角度,单位:弧度 */ |                         .lf_hip = -0.50f,   /* 左前腿髋关节最大角度,单位:弧度 */ | ||||||
| @ -97,29 +102,26 @@ Config_t param_default = { | |||||||
|                 } |                 } | ||||||
|             }, |             }, | ||||||
| 
 | 
 | ||||||
| 
 |  | ||||||
|             .zero_point = { |             .zero_point = { | ||||||
|                 .named = { |                 .named = { | ||||||
|                     .lf_hip = 0.02f,   /* 左前腿髋关节零点角度,单位:弧度 */ |                     .lf_hip = 0.02f,   /* 左前腿髋关节零点角度,单位:弧度 */ | ||||||
|                     .lf_thigh = -3.17f, /* 左前腿大腿零点角度,单位:弧度 */ |                     .lf_thigh = -4.90f, /* 左前腿大腿零点角度,单位:弧度 */ | ||||||
|                     .lf_calf = 0.72f - JOINT_CALF_OFFSET,  /* 左前腿小腿零点角度,单位:弧度 */ |                     .lf_calf = 0.9f - JOINT_CALF_OFFSET,  /* 左前腿小腿零点角度,单位:弧度 */ | ||||||
| 
 | 
 | ||||||
|                     .rf_hip = 5.37f,   /* 右前腿髋关节零点角度,单位:弧度 */ |                     .rf_hip = 5.27f,   /* 右前腿髋关节零点角度,单位:弧度 */ | ||||||
|                     .rf_thigh = 9.38f, /* 右前腿大腿零点角度,单位:弧度 */ |                     .rf_thigh = 9.443f, /* 右前腿大腿零点角度,单位:弧度 */ | ||||||
|                     .rf_calf = 4.96f + JOINT_CALF_OFFSET,  /* 右前腿小腿零点角度,单位:弧度 */ |                     .rf_calf = 6.02777243f + JOINT_CALF_OFFSET,  /* 右前腿小腿零点角度,单位:弧度 */ | ||||||
| 
 | 
 | ||||||
|                     .lr_hip = 4.5f,   /* 左后腿髋关节零点角度,单位:弧度 */ |                     .lr_hip = 4.5f,   /* 左后腿髋关节零点角度,单位:弧度 */ | ||||||
|                     .lr_thigh = -3.2f, /* 左后腿大腿零点角度,单位:弧度 */ |                     .lr_thigh = -3.2f, /* 左后腿大腿零点角度,单位:弧度 */ | ||||||
|                     .lr_calf = 1.73f - JOINT_CALF_OFFSET,  /* 左后腿小腿零点角度,单位:弧度 */ |                     .lr_calf = 1.22f - JOINT_CALF_OFFSET,  /* 左后腿小腿零点角度,单位:弧度 */ | ||||||
| 
 | 
 | ||||||
|                     .rr_hip = 2.7f,   /* 右后腿髋关节零点角度,单位:弧度 */ |                     .rr_hip = 2.55f,   /* 右后腿髋关节零点角度,单位:弧度 */ | ||||||
|                     .rr_thigh = 10.58f, /* 右后腿大腿零点角度,单位:弧度 */ |                     .rr_thigh = 10.45f, /* 右后腿大腿零点角度,单位:弧度 */ | ||||||
|                     .rr_calf = 3.58f + JOINT_CALF_OFFSET,  /* 右后腿小腿零点角度,单位:弧度 */ |                     .rr_calf = 3.48f + JOINT_CALF_OFFSET,  /* 右后腿小腿零点角度,单位:弧度 */ | ||||||
|                 } |                 } | ||||||
|             }, |             }, | ||||||
| 
 | 
 | ||||||
| 
 |  | ||||||
| 
 |  | ||||||
|             .sign = { |             .sign = { | ||||||
|                 .leg = { |                 .leg = { | ||||||
|                     [0] = { .hip = 1, .thigh = 1, .calf = -1 }, /* 左前腿 */ |                     [0] = { .hip = 1, .thigh = 1, .calf = -1 }, /* 左前腿 */ | ||||||
| @ -128,6 +130,7 @@ Config_t param_default = { | |||||||
|                     [3] = { .hip = 1, .thigh = -1, .calf = 1 },   /* 右后腿 */ |                     [3] = { .hip = 1, .thigh = -1, .calf = 1 },   /* 右后腿 */ | ||||||
|                 } |                 } | ||||||
|             }, |             }, | ||||||
|  | 
 | ||||||
|             .ratio = { |             .ratio = { | ||||||
|                 .named = { |                 .named = { | ||||||
|                     .lf_hip = 6.33f,   /* 左前腿髋关节减速比 */ |                     .lf_hip = 6.33f,   /* 左前腿髋关节减速比 */ | ||||||
| @ -144,15 +147,13 @@ Config_t param_default = { | |||||||
|                     .rr_calf = 12.66f, /* 右后腿小腿减速比 */ |                     .rr_calf = 12.66f, /* 右后腿小腿减速比 */ | ||||||
|                 } |                 } | ||||||
|             }, |             }, | ||||||
|  | 
 | ||||||
|             .leg_offset = { |             .leg_offset = { | ||||||
|                 .x = 0.19625f, /* 腿偏移X轴,单位:米 */ |                 .x = 0.19625f, /* 腿偏移X轴,单位:米 */ | ||||||
|                 .y = 0.0825f, /* 腿偏移Y轴,单位:米 */ |                 .y = 0.0825f, /* 腿偏移Y轴,单位:米 */ | ||||||
|                 .z = 0.0f, /* 腿偏移Z轴,单位:米 */ |                 .z = 0.0f, /* 腿偏移Z轴,单位:米 */ | ||||||
|             } |             } | ||||||
| 
 |  | ||||||
|         }, |         }, | ||||||
| 
 |  | ||||||
| 
 |  | ||||||
|     }, |     }, | ||||||
| }; /* param_default */ | }; /* param_default */ | ||||||
| 
 | 
 | ||||||
|  | |||||||
		Loading…
	
		Reference in New Issue
	
	Block a user