首页 星云 工具 资源 星选 资讯 热门工具
:

PDF转图片 完全免费 小红书视频下载 无水印 抖音视频下载 无水印 数字星空

Differential-Drive-Robot-main.zip

行业研究 882.41KB 10 需要积分: 1
立即下载

资源介绍:

Differential-Drive-Robot-main.zip
## Overview This repo contains the code for controlling both a real and a simulated differential drive robot via ROS2 using different planners, controllers, and open-source libraries for slam and odometry. ## List of available controllers 1. Approximate linearization 2. Input-Output linearization 3. Input-Output linearization + Linear MPC via Casadi 4. Dynamic linearization 5. Nonlinear Lyapunov 6. Nonlinear MPC via Casadi 7. Nonlinear MPC via Acados 8. Iterative Linear Quadratic Regulator 9. Iterative Linear Quadratic Regulator via Crocoddyl 10. Predictive Sampling MPC ## List of available planners 1. A* 2. Breadth First search 3. Djikstra 4. Greedy Best First search 5. RRT 6. RRT* (in progress) 7. RRT-primitives ## Repository structure It includes the following folders and subfolders: 1. ```python_scripts```: most of the ROS2 nodes call some classes here 2. ```coppeliasim_simulation```: scenes used for simulating the robot (dynamically enabled or not) 3. ```ros2_ws```: collection of ROS2 nodes for controlling the robot with the aid of some external tools such as ```slam_toolbox``` (generate a map and localization) and ```kiss-icp``` (lidar odometry) ## Dependencies 1. [ROS2 Humble](https://docs.ros.org/en/humble/Installation.html) 2. [CoppeliaSim](https://www.coppeliarobotics.com/downloads) 3. [kiss-icp](https://github.com/PRBonn/kiss-icp) 4. [slam_toolbox](https://github.com/SteveMacenski/slam_toolbox) ## Build on linux 1. clone the repo ```sh git clone --recurse-submodules https://github.com/giulioturrisi/differential_drive.git ``` 2. extract CoppeliaSim in Differential-Drive-Robot/coppeliasim_simulation 3. add the following ls in ros2_ws/src/simExtROS2/meta/interfaces.txt ```sh geometry_msgs/msg/Twist geometry_msgs/msg/TwistStamped sensor_msgs/msg/LaserScan ``` 4. build the docker file inside Differential-Drive-Robot/docker_file/integrated_gpu or /nvidia ```sh docker build -t ros2_humble . ``` 5. add alias to start the docker ```sh cd gedit .bashrc alias ddrive_humble='xhost + && docker run -it --rm -v /path/to/your_folder/Differential-Drive-Robot:/home/ -v /tmp/.X11-unix:/tmp/.X11-unix:rw --device=/dev/input/ -e DISPLAY=$DISPLAY -e WAYLAND_DISPLAY=$WAYLAND_DISPLAY -e QT_X11_NO_MITSHM=1 --gpus all --name ddrive_humble ros2_humble' (if used /nvidia) alias ddrive_humble="xhost + && docker run -it --rm -v /path/to/your_folder/Differential-Drive-Robot:/home/ -v /tmp/.X11-unix:/tmp/.X11-unix --device=/dev/dri --device=/dev/input/ -e DISPLAY=$DISPLAY -e WAYLAND_DISPLAY=$WAYLAND_DISPLAY --name ddrive_humble ros2_humble" (if used /integrated_gpu) alias ddrive_humble='xhost + && docker run -it --rm -v /path/to/your_folder/Differential-Drive-Robot:/home/ -v /tmp/.X11-unix:/tmp/.X11-unix -v /mnt/wslg:/mnt/wslg -v /usr/lib/wsl:/usr/lib/wsl --device=/dev/dxg -e DISPLAY=$DISPLAY -e WAYLAND_DISPLAY=$WAYLAND_DISPLAY -e XDG_RUNTIME_DIR=$XDG_RUNTIME_DIR -e PULSE_SERVER=$PULSE_SERVER -e LD_LIBRARY_PATH=/usr/lib/wsl/lib --name ddrive_humble ros2_humble' (if Windows Linux Subsystem) alias ddrive='docker exec -it ddrive_humble bash' (to attach a new terminal to the running docker) ``` 6. start docker and build ```sh ddrive_humble cd ros2_ws rosdep install -y -r -q --from-paths src --ignore-src --rosdistro humble ulimit -s unlimited colcon build --symlink-install ``` ## How to run the simulation All the commands below can be easily launched via some aliases. Check them by activating the docker ```ddrive_humble``` and writing on the keyboard ```launch_``` (plus tab for the autocomplete) Follow the commands below to run all the framework: 1. on a new terminal first launch the simulation ```sh launch_sim_kinematics (scene with kinematics) launch_sim_dynamics (scene with dynamics) ``` 2. on each new terminal, then launch all the other packages ```sh launch_joy (to use the joystick) launch_rviz (visualization) launch_planners (planning) launch_controllers (control) launch_lidar_odometry (tf and kiss-icp) launch_slam (slam-toolbox) ros2 launch ydlidar_ros2_driver ydlidar_launch.py (ydlidar - only real robot) ``` 3. you can choose a goal pose in Rviz2 clicking 2D Goal Pose ## Status Still working in progress, the real robot exists but it's not yet finalized!

资源文件列表:

Differential-Drive-Robot-main.zip 大约有178个文件
  1. Differential-Drive-Robot-main/
  2. Differential-Drive-Robot-main/.gitignore 384B
  3. Differential-Drive-Robot-main/.gitmodules 905B
  4. Differential-Drive-Robot-main/README.md 4.57KB
  5. Differential-Drive-Robot-main/coppeliasim_simulation/
  6. Differential-Drive-Robot-main/coppeliasim_simulation/dynamics.ttt 400.47KB
  7. Differential-Drive-Robot-main/coppeliasim_simulation/kinematics.ttt 399.78KB
  8. Differential-Drive-Robot-main/coppeliasim_simulation/urdf_from_coppelia/
  9. Differential-Drive-Robot-main/coppeliasim_simulation/urdf_from_coppelia/differential_drive.urdf 3.82KB
  10. Differential-Drive-Robot-main/coppeliasim_simulation/urdf_from_coppelia/differential_drive_Hokuyo_URG_04LX_UG01_body__70__.dae 51.16KB
  11. Differential-Drive-Robot-main/installation/
  12. Differential-Drive-Robot-main/installation/conda/
  13. Differential-Drive-Robot-main/installation/conda/mamba_environment.yml 330B
  14. Differential-Drive-Robot-main/installation/docker_file/
  15. Differential-Drive-Robot-main/installation/docker_file/integrated_gpu/
  16. Differential-Drive-Robot-main/installation/docker_file/integrated_gpu/dockerfile 5.36KB
  17. Differential-Drive-Robot-main/installation/docker_file/nvidia/
  18. Differential-Drive-Robot-main/installation/docker_file/nvidia/dockerfile 5.72KB
  19. Differential-Drive-Robot-main/installation/docker_file/nvidia_cuda/
  20. Differential-Drive-Robot-main/installation/docker_file/nvidia_cuda/dockerfile 6.45KB
  21. Differential-Drive-Robot-main/python_scripts/
  22. Differential-Drive-Robot-main/python_scripts/controllers/
  23. Differential-Drive-Robot-main/python_scripts/controllers/acados/
  24. Differential-Drive-Robot-main/python_scripts/controllers/acados/acados/
  25. Differential-Drive-Robot-main/python_scripts/controllers/acados/acados_model.py 1.29KB
  26. Differential-Drive-Robot-main/python_scripts/controllers/acados/acados_nmpc.py 4.72KB
  27. Differential-Drive-Robot-main/python_scripts/controllers/acados/test.py 3.64KB
  28. Differential-Drive-Robot-main/python_scripts/controllers/approximate_linearization.py 2.88KB
  29. Differential-Drive-Robot-main/python_scripts/controllers/casadi_nmpc.py 7.11KB
  30. Differential-Drive-Robot-main/python_scripts/controllers/crocoddyl/
  31. Differential-Drive-Robot-main/python_scripts/controllers/crocoddyl/test_model_cpp.py 882B
  32. Differential-Drive-Robot-main/python_scripts/controllers/crocoddyl/test_model_num_diff.py 2.62KB
  33. Differential-Drive-Robot-main/python_scripts/controllers/crocoddyl/test_model_python.py 2.56KB
  34. Differential-Drive-Robot-main/python_scripts/controllers/dynamic_linearization.py 3.21KB
  35. Differential-Drive-Robot-main/python_scripts/controllers/ilqr.py 10.52KB
  36. Differential-Drive-Robot-main/python_scripts/controllers/io_linearization.py 1.98KB
  37. Differential-Drive-Robot-main/python_scripts/controllers/io_linearization_mpc.py 5.81KB
  38. Differential-Drive-Robot-main/python_scripts/controllers/nonlinear_lyapunov.py 2.74KB
  39. Differential-Drive-Robot-main/python_scripts/controllers/predictive_sampling.py 14.06KB
  40. Differential-Drive-Robot-main/python_scripts/maps/
  41. Differential-Drive-Robot-main/python_scripts/maps/map.pgm 140.32KB
  42. Differential-Drive-Robot-main/python_scripts/path_utilities.py 2.21KB
  43. Differential-Drive-Robot-main/python_scripts/planners/
  44. Differential-Drive-Robot-main/python_scripts/planners/grid_based/
  45. Differential-Drive-Robot-main/python_scripts/planners/grid_based/a_star.py 8KB
  46. Differential-Drive-Robot-main/python_scripts/planners/grid_based/breadth_first_search.py 6.83KB
  47. Differential-Drive-Robot-main/python_scripts/planners/grid_based/djikstra.py 7.55KB
  48. Differential-Drive-Robot-main/python_scripts/planners/grid_based/greedy_best_first_search.py 7.49KB
  49. Differential-Drive-Robot-main/python_scripts/planners/sampling_based/
  50. Differential-Drive-Robot-main/python_scripts/planners/sampling_based/rrt.py 7.75KB
  51. Differential-Drive-Robot-main/python_scripts/planners/sampling_based/rrt_primitives.py 8.76KB
  52. Differential-Drive-Robot-main/python_scripts/planners/sampling_based/rrt_star.py 7B
  53. Differential-Drive-Robot-main/python_scripts/robot_model.py 2.93KB
  54. Differential-Drive-Robot-main/python_scripts/test/
  55. Differential-Drive-Robot-main/python_scripts/test/test_controllers.py 5.71KB
  56. Differential-Drive-Robot-main/python_scripts/test/test_planning_time.py 2.33KB
  57. Differential-Drive-Robot-main/python_scripts/test/test_single_planner.py 1.33KB
  58. Differential-Drive-Robot-main/ros2_ws/
  59. Differential-Drive-Robot-main/ros2_ws/src/
  60. Differential-Drive-Robot-main/ros2_ws/src/controllers/
  61. Differential-Drive-Robot-main/ros2_ws/src/controllers/controllers/
  62. Differential-Drive-Robot-main/ros2_ws/src/controllers/controllers/__init__.py
  63. Differential-Drive-Robot-main/ros2_ws/src/controllers/controllers/base_controller.py 4.74KB
  64. Differential-Drive-Robot-main/ros2_ws/src/controllers/controllers/run_controllers.py 8.26KB
  65. Differential-Drive-Robot-main/ros2_ws/src/controllers/package.xml 945B
  66. Differential-Drive-Robot-main/ros2_ws/src/controllers/resource/
  67. Differential-Drive-Robot-main/ros2_ws/src/controllers/resource/controllers
  68. Differential-Drive-Robot-main/ros2_ws/src/controllers/setup.cfg 91B
  69. Differential-Drive-Robot-main/ros2_ws/src/controllers/setup.py 1.25KB
  70. Differential-Drive-Robot-main/ros2_ws/src/controllers/test/
  71. Differential-Drive-Robot-main/ros2_ws/src/controllers/test/test_copyright.py 962B
  72. Differential-Drive-Robot-main/ros2_ws/src/controllers/test/test_flake8.py 884B
  73. Differential-Drive-Robot-main/ros2_ws/src/controllers/test/test_pep257.py 803B
  74. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/
  75. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/CMakeLists.txt 1.01KB
  76. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/COLCON_IGNORE
  77. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/Findpigpio.cmake 1.05KB
  78. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/include/
  79. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/include/rotary_encoder.cpp 2.26KB
  80. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/include/rotary_encoder.hpp 752B
  81. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/package.xml 741B
  82. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/src/
  83. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/src/motor.cpp 13.65KB
  84. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/src/test.cpp 4KB
  85. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/
  86. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/
  87. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/CMakeLists.txt 724B
  88. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/Findpigpio.cmake 1.05KB
  89. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/
  90. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeCache.txt 12.36KB
  91. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/
  92. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/
  93. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/CMakeCCompiler.cmake 2.17KB
  94. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/CMakeCXXCompiler.cmake 4.74KB
  95. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/CMakeDetermineCompilerABI_C.bin 8.85KB
  96. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/CMakeDetermineCompilerABI_CXX.bin 9.03KB
  97. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/CMakeSystem.cmake 388B
  98. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/CompilerIdC/
  99. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/CompilerIdC/CMakeCCompilerId.c 17.65KB
  100. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/CompilerIdC/a.out 9.03KB
  101. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/CompilerIdCXX/
  102. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/CompilerIdCXX/CMakeCXXCompilerId.cpp 17.22KB
  103. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/3.10.2/CompilerIdCXX/a.out 9.2KB
  104. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/CMakeDirectoryInformation.cmake 652B
  105. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/CMakeOutput.log 43.44KB
  106. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/Makefile.cmake 1.73KB
  107. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/Makefile2 3.12KB
  108. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/TargetDirectories.txt 205B
  109. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/cmake.check_cache 85B
  110. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/
  111. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/CXX.includecache 571B
  112. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/DependInfo.cmake 764B
  113. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/build.make 6.33KB
  114. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/cmake_clean.cmake 295B
  115. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/depend.internal 394B
  116. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/depend.make 344B
  117. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/flags.make 290B
  118. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/link.txt 165B
  119. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/progress.make 64B
  120. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/rotary_encoder.cpp.o 4.04KB
  121. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/dc_motor.dir/test.cpp.o 95.89KB
  122. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/feature_tests.bin 12.98KB
  123. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/feature_tests.c 688B
  124. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/feature_tests.cxx 9.78KB
  125. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/CMakeFiles/progress.marks 2B
  126. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/Makefile 5.52KB
  127. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/cmake_install.cmake 1.49KB
  128. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/data_log.txt
  129. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/build/dc_motor 52.19KB
  130. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/rotary_encoder.cpp 2.92KB
  131. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/rotary_encoder.hpp 754B
  132. Differential-Drive-Robot-main/ros2_ws/src/driver_motor/test/dc_motor_l298N/test.cpp 7.42KB
  133. Differential-Drive-Robot-main/ros2_ws/src/external/
  134. Differential-Drive-Robot-main/ros2_ws/src/external/kiss-icp/
  135. Differential-Drive-Robot-main/ros2_ws/src/external/pointcloud_to_laserscan/
  136. Differential-Drive-Robot-main/ros2_ws/src/external/ros2_bubble_rob/
  137. Differential-Drive-Robot-main/ros2_ws/src/external/simROS2/
  138. Differential-Drive-Robot-main/ros2_ws/src/external/tf_transformations/
  139. Differential-Drive-Robot-main/ros2_ws/src/planners/
  140. Differential-Drive-Robot-main/ros2_ws/src/planners/package.xml 942B
  141. Differential-Drive-Robot-main/ros2_ws/src/planners/planners/
  142. Differential-Drive-Robot-main/ros2_ws/src/planners/planners/__init__.py
  143. Differential-Drive-Robot-main/ros2_ws/src/planners/planners/run_planners.py 9.45KB
  144. Differential-Drive-Robot-main/ros2_ws/src/planners/resource/
  145. Differential-Drive-Robot-main/ros2_ws/src/planners/resource/planners
  146. Differential-Drive-Robot-main/ros2_ws/src/planners/setup.cfg 85B
  147. Differential-Drive-Robot-main/ros2_ws/src/planners/setup.py 656B
  148. Differential-Drive-Robot-main/ros2_ws/src/planners/test/
  149. Differential-Drive-Robot-main/ros2_ws/src/planners/test/test_copyright.py 962B
  150. Differential-Drive-Robot-main/ros2_ws/src/planners/test/test_flake8.py 884B
  151. Differential-Drive-Robot-main/ros2_ws/src/planners/test/test_pep257.py 803B
  152. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/
  153. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/launch/
  154. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/launch/state_publisher_launch.py 1.67KB
  155. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/package.xml 711B
  156. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/resource/
  157. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/resource/state_estimation
  158. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/setup.cfg 101B
  159. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/setup.py 932B
  160. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/state_estimation/
  161. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/state_estimation/__init__.py
  162. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/state_estimation/state_publisher.py 5.02KB
  163. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/test/
  164. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/test/test_copyright.py 962B
  165. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/test/test_flake8.py 884B
  166. Differential-Drive-Robot-main/ros2_ws/src/state_estimation/test/test_pep257.py 803B
  167. Differential-Drive-Robot-main/ros2_ws/src/utilities/
  168. Differential-Drive-Robot-main/ros2_ws/src/utilities/command.txt 250B
  169. Differential-Drive-Robot-main/ros2_ws/src/utilities/maps/
  170. Differential-Drive-Robot-main/ros2_ws/src/utilities/maps/simple_walls/
  171. Differential-Drive-Robot-main/ros2_ws/src/utilities/maps/simple_walls/simple_walls_map.data 115.92KB
  172. Differential-Drive-Robot-main/ros2_ws/src/utilities/maps/simple_walls/simple_walls_map.pgm 3.24KB
  173. Differential-Drive-Robot-main/ros2_ws/src/utilities/maps/simple_walls/simple_walls_map.posegraph 4.87MB
  174. Differential-Drive-Robot-main/ros2_ws/src/utilities/maps/simple_walls/simple_walls_map.yaml 134B
  175. Differential-Drive-Robot-main/ros2_ws/src/utilities/plotjuggler_config/
  176. Differential-Drive-Robot-main/ros2_ws/src/utilities/plotjuggler_config/plot_juggler_ddrive.xml 5.72KB
  177. Differential-Drive-Robot-main/ros2_ws/src/utilities/rviz_config/
  178. Differential-Drive-Robot-main/ros2_ws/src/utilities/rviz_config/common.rviz 9.06KB
0评论
提交 加载更多评论
其他资源 CSS技巧专栏一日一例:19 -纯CSS实现超酷的水晶按钮特效.zip
CSS技巧专栏一日一例:19 -纯CSS实现超酷的水晶按钮特效.zip --------------------------------------------------------------------------------------------------------- 需要看看效果的,可以移步到我的专栏去看看。文章名与资源名一致。 资源特点:代码短小、代码容易阅读、重点注释、方便扩展、样式美观、纯CSS实现。 适用人群:前端从业职,新手小白,有网站开发能力对美工有所欠缺的后端工程师。
JS+CSS案例:可适应上下布局和左右布局的菜单(含二级菜单).zip
JS+CSS案例:可适应上下布局和左右布局的菜单(含二级菜单)。如题所述,这是一个可以通过前端页面的切换样式表改变菜单位置布局的一个案例。案例是非常时尚且实用的二级菜单。 --------------------------------------------------------------------------------------------------------- 需要看看效果的,可以移步到我的专栏去看看。文章名与资源名一致。 资源特点:代码短小、代码容易阅读、重点注释、方便扩展、样式美观、CSS+JS实现。 适用人群:前端从业职,新手小白,有网站开发能力对美工有所欠缺的后端工程师。
人体姿势识别yolo8预训练模型,内附完整Python运行代码,可直接运行,可用于图片或者视频的人体姿势识别
项目:人体姿势识别预训练模型 用途: 可以直接用于人体姿势识别, 也可以作为基础模型再训练 预测效果: 资源内附唐朝诡事录经典站位图识别效果,可以准确识别出面部和躯体。 人体姿势识别的作用: 人体姿势识别预训练模型是一种在计算机视觉领域中具有重要应用的技术。 它是通过使用大量的人体姿势相关数据进行训练得到的模型。这些数据通常包含了各种不同场景、不同个体、不同动作下的人体图像或视频帧。 预训练模型的优势在于它能够学习到通用的人体姿势特征和模式。例如,它可以识别出站立、坐下、跑步、跳跃等常见姿势,还能区分不同身体部位的位置和姿态关系。 在实际应用中,人体姿势识别预训练模型有着广泛的用途。比如在运动分析领域,它可以帮助教练评估运动员的动作是否标准,以便进行针对性的训练改进;在医疗康复领域,用于监测患者的康复训练动作是否正确;在虚拟现实和增强现实中,实现对用户身体动作的准确捕捉和响应,提供更加沉浸式的体验。 总之,人体姿势识别预训练模型为许多领域带来了创新和便利,随着技术的不断发展,其性能和应用范围还将不断扩大。
gdal1111-192.zip
gdal1111、gdal192、gdal1113、gdal1115源码合集
基于MATLAB的交通标志识别(完美运行)
交通标志识别是指通过计算机视觉技术,识别和理解道路上的交通标志。这项技术是自动驾驶、智能交通系统等领域的重要组成部分。 交通标志识别的步骤通常包括以下几个方面: 1. 图像采集:使用摄像头或其他传感器采集道路上的交通标志图像。 2. 图像预处理:对采集到的图像进行预处理,包括图像去噪、图像增强等操作,以提高后续识别的准确性。 3. 特征提取:从预处理后的图像中提取出有用的特征信息,如形状、颜色、纹理等特征。 4. 分类识别:使用机器学习或深度学习算法对提取的特征进行分类,将图像分为不同的交通标志类别。 5. 结果输出:将识别结果输出给相关系统,如自动驾驶系统,以做出相应的决策。 为了提高交通标志识别的准确性和效率,研究人员通常会采用一系列的算法和技术,如卷积神经网络(CNN)、支持向量机(SVM)等。同时,还需要大量的标注数据集进行训练和测试。 交通标志识别不仅可以应用在自动驾驶领域,还可以用于智能交通管理系统、交通违法监控等场景,提高交通安全性和效率。
基于MATLAB的火焰检测定位(完美运行)
火焰检测定位是指利用各种传感器和技术手段来检测和定位火焰的位置。这可以帮助人们迅速发现火灾并采取相应的应急措施,以减少火灾对人员和财产的伤害。 火焰检测定位系统通常包括以下几个主要组成部分: 1. 火焰传感器:利用红外线、紫外线、热像仪等技术,可以检测到火焰释放的特定波长或热量,从而确定火焰的存在。 2. 信号处理器:对传感器检测到的信号进行处理和分析,以区分真实火焰信号和误报信号,并提取火焰的位置信息。 3. 定位算法:利用信号处理器提供的数据,采用各种定位算法来计算火焰的位置坐标。常见的定位算法包括三角测量法、梯度法、质心法等。 4. 显示和报警装置:将火焰的位置信息显示在监控屏幕或其他设备上,同时触发相应的报警装置(如声音、灯光、短信等),以及时通知相关人员。 火焰检测定位系统广泛应用于各类场所,如工厂、仓库、办公楼、地铁站等,以及一些特殊环境,如化工厂、石油平台等。这些系统可以帮助消防人员快速发现火灾,及时采取救援行动,从而减少火灾造成的损失。
2021-CUMCM-C-yasNing.zip
2021-CUMCM-C-yasNing.zip
基于Web的社区医院管理服务系统
基于java敬老院管理系统