├── README.md ├── img ├── agilex_open_class.png └── 松灵ROS 2开讲啦.jpg ├── limo ├── README.md ├── image │ ├── limo_ackerman.png │ ├── limo_diff.png │ └── rviz.png ├── limo_bringup │ ├── CMakeLists.txt │ ├── config_files │ │ ├── demo_2d.rviz │ │ ├── ekf.yaml │ │ ├── limo_laser.lua │ │ ├── limo_lds_2d.lua │ │ ├── limon_navigation.rviz │ │ └── slam_box.yaml │ ├── launch │ │ ├── __pycache__ │ │ │ ├── cartographer.launch.cpython-310.pyc │ │ │ └── occupancy_grid.launch.cpython-310.pyc │ │ └── humble │ │ │ ├── __pycache__ │ │ │ └── limo_rtab_nav2.laun.cpython-310.pyc │ │ │ ├── bringup.launch.py │ │ │ ├── ekf_odom.launch.py │ │ │ ├── limo_cartographer.launch copy.py │ │ │ ├── limo_cartographer.launch.py │ │ │ ├── limo_nav2.launch.py │ │ │ ├── limo_nav2_explore.launch.py │ │ │ ├── limo_rtab_nav2.launch.py │ │ │ ├── limo_rtab_rgbd.launch.py │ │ │ ├── limo_rtab_scan.launch.py │ │ │ ├── limo_slam_box.launch.py │ │ │ ├── limo_start.launch.py │ │ │ ├── localization_launch.py │ │ │ ├── navigation_launch.py │ │ │ └── rgbdslam_datasets.launch.py │ ├── maps │ │ ├── limo.pgm │ │ ├── limo.yaml │ │ ├── map.pgm │ │ ├── map.yaml │ │ ├── map01.pgm │ │ ├── map01.yaml │ │ ├── map02.pgm │ │ ├── map02.yaml │ │ ├── map03.pgm │ │ ├── map03.yaml │ │ ├── map04.pgm │ │ ├── map04.yaml │ │ ├── map212.pgm │ │ ├── map212.yaml │ │ ├── map222 (copy).pgm │ │ ├── map222.pgm │ │ └── map222.yaml │ ├── package.xml │ ├── param │ │ ├── amcl_params.yaml │ │ ├── costmap_common.yaml │ │ ├── costmap_global_laser.yaml │ │ ├── costmap_global_static.yaml │ │ ├── costmap_local.yaml │ │ ├── nav2.yaml │ │ ├── nav2_ackermann.yaml │ │ ├── nav2_ackermann_foxy.yaml │ │ ├── nav2_ackermann_rtab.yaml │ │ ├── nav2_explore.yaml │ │ ├── planner.yaml │ │ └── ydlidar.yaml │ ├── readme.md │ ├── rviz │ │ ├── cartographer.rviz │ │ ├── nav2.rviz │ │ ├── nav2_copy.rviz │ │ └── nav2_rtab.rviz │ ├── scripts │ │ ├── mpu6050_test │ │ │ ├── blinkatest.py │ │ │ ├── simple_test.py │ │ │ ├── use_smbus.py │ │ │ └── use_smbus_2.py │ │ └── start_build_map_2d_ros2.sh │ └── setup.py ├── limo_description │ ├── CMakeLists.txt │ ├── img │ │ └── limo.jpg │ ├── launch │ │ ├── display_limo_ackerman.launch.py │ │ └── display_limo_diff.launch.py │ ├── meshes │ │ ├── limo_base.dae │ │ ├── limo_base.stl │ │ ├── limo_wheel.dae │ │ └── limo_wheel.stl │ ├── package.xml │ ├── rviz │ │ └── model_display.rviz │ └── urdf │ │ ├── limo_ackerman.gazebo │ │ ├── limo_ackerman.xacro │ │ ├── limo_ackerman_gazebo.gazebo │ │ ├── limo_four_diff.gazebo │ │ ├── limo_four_diff.xacro │ │ ├── limo_gazebo.gazebo │ │ ├── limo_steering_hinge.xacro │ │ └── limo_xacro.xacro ├── limo_gazebo_sim │ ├── CMakeLists.txt │ ├── config │ │ ├── limo_ackerman_control.yaml │ │ └── limo_four_diff_control.yaml │ ├── launch │ │ ├── limo_ackerman.launch.py │ │ ├── limo_ackerman_empty_world.launch.py │ │ ├── limo_ackerman_spawn.launch.py │ │ ├── limo_diff.launch.py │ │ ├── limo_diff_empty_world.launch.py │ │ └── limo_diff_spawn.launch.py │ ├── package.xml │ └── worlds │ │ ├── clearpath_playpen.world │ │ ├── empty.world │ │ ├── willowgarage.world │ │ ├── world_v1.world │ │ └── world_v1 │ │ ├── model.config │ │ └── model.sdf ├── limo_learnning │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ │ ├── action.cpp │ │ ├── explore.cpp │ │ ├── follow_path.cpp │ │ ├── limo_action_client.cpp │ │ ├── limo_action_server.cpp │ │ ├── limo_client.cpp │ │ ├── limo_scan.cpp │ │ ├── limo_scan_nav.cpp │ │ ├── limo_server.cpp │ │ ├── limo_topic_cmd.cpp │ │ ├── listen_tf.cpp │ │ ├── multi_goal_nav.cpp │ │ ├── multi_goal_nav_back.cpp │ │ └── record_path.cpp ├── limo_learnning_py │ ├── limo_learnning_py │ │ ├── __init__.py │ │ ├── limo_action_client.py │ │ ├── limo_action_server.py │ │ ├── limo_client.py │ │ ├── limo_scan.py │ │ ├── limo_server.py │ │ ├── limo_topic_cmd.py │ │ └── multi_goal_nav.py │ ├── package.xml │ ├── resource │ │ └── limo_learnning_py │ ├── setup.cfg │ ├── setup.py │ └── test │ │ ├── test_copyright.py │ │ ├── test_flake8.py │ │ └── test_pep257.py └── limo_msgs │ ├── CMakeLists.txt │ ├── action │ └── LimoAction.action │ ├── msg │ └── LimoStatus.msg │ ├── package.xml │ └── srv │ └── LimoSrv.srv └── piper ├── README.md ├── image ├── piper.png ├── piper_gazebo.png ├── piper_gazebo_moveit.png └── piper_moveit.png ├── learnning_piper ├── CMakeLists.txt ├── package.xml └── src │ ├── move_multi_target.cpp │ ├── move_target.cpp │ └── moveit_cpp_tutorial.cpp ├── piper_description ├── CMakeLists.txt ├── config │ ├── joint_name_piper_description.yaml │ ├── joint_names_agx_arm_description.yaml │ └── piper_gazebo_control.yaml ├── launch │ ├── display_piper.launch.py │ ├── piper_empty_world.launch.py │ ├── piper_gazebo.launch.py │ └── piper_spawn.launch.py ├── meshes │ ├── base_link.STL │ ├── link1.STL │ ├── link2.STL │ ├── link3.STL │ ├── link4.STL │ ├── link5.STL │ ├── link6.STL │ ├── link7.STL │ └── link8.STL ├── package.xml ├── rviz │ └── piper_ctrl.rviz ├── urdf │ ├── piper_description.csv │ ├── piper_description.urdf │ ├── piper_description.xacro │ └── piper_description_gazebo.xacro └── worlds │ └── empty.world ├── piper_moveit_config_v4 ├── .setup_assistant ├── CMakeLists.txt ├── config │ ├── initial_positions.yaml │ ├── joint_limits.yaml │ ├── kinematics.yaml │ ├── moveit.rviz │ ├── moveit_controllers.yaml │ ├── pilz_cartesian_limits.yaml │ ├── piper.ros2_control.xacro │ ├── piper.srdf │ ├── piper.urdf.xacro │ └── ros2_controllers.yaml ├── launch │ ├── demo.launch.py │ ├── move_group.launch.py │ ├── moveit_rviz.launch.py │ ├── rsp.launch.py │ ├── setup_assistant.launch.py │ ├── spawn_controllers.launch.py │ ├── static_virtual_joint_tfs.launch.py │ └── warehouse_db.launch.py └── package.xml └── piper_moveit_config_v5 ├── .setup_assistant ├── CMakeLists.txt ├── config ├── initial_positions.yaml ├── joint_limits.yaml ├── kinematics.yaml ├── moveit.rviz ├── moveit_controllers.yaml ├── pilz_cartesian_limits.yaml ├── piper.ros2_control.xacro ├── piper.srdf ├── piper.urdf.xacro └── ros2_controllers.yaml ├── launch ├── demo.launch.py ├── move_group.launch.py ├── moveit_rviz.launch.py ├── rsp.launch.py ├── setup_assistant.launch.py ├── spawn_controllers.launch.py ├── static_virtual_joint_tfs.launch.py └── warehouse_db.launch.py └── package.xml /README.md: -------------------------------------------------------------------------------- 1 | # 松灵 ROS2 开讲啦! 2 | ![img](img/agilex_open_class.png) 3 | -------------------------------------------------------------------------------- /img/agilex_open_class.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/img/agilex_open_class.png -------------------------------------------------------------------------------- /img/松灵ROS 2开讲啦.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/img/松灵ROS 2开讲啦.jpg -------------------------------------------------------------------------------- /limo/README.md: -------------------------------------------------------------------------------- 1 | # LIMO环境配置过程 2 | 3 | ## 1. 功能包介绍 4 | 5 | ``` 6 | ├── image 7 | ├── limo_description 8 | ├── limo_gazebo_sim 9 | ``` 10 | 11 | ​ limo_description: 模型描述文件功能包 12 | 13 | ​ limo_gazebo_sim: gazebo仿真启动功能包 14 | 15 | ## 2. 使用环境 16 | 17 | ### Development Environment 18 | 19 | ​ ubuntu 22.04 + [RO2 humble desktop full](http://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html) 20 | 21 | ### 需要下载的功能包 22 | 23 | ​ 下载安装gazebo相关的依赖和gazebo-ros-control等功能包;gazebo-ros是gazebo与ROS之间的通信接口,连接ROS与Gazebo 24 | 25 | ``` 26 | sudo apt-get install ros-humble-gazebo-* 27 | ``` 28 | 29 | ​ 下载并安装 joint-state-publisher-gui joint-state-publisher 。这两个功能包是用于发布关节信息的 30 | 31 | ``` 32 | sudo apt-get install ros-humble-joint-state-publisher ros-humble-joint-state-publisher-gui 33 | ``` 34 | 35 | ​ 下载并安装diff-drive-controller;diff-drive-controller是用于控制车子的gazebo插件 36 | 37 | ``` 38 | sudo apt-get install ros-humble-diff-drive-controller 39 | ``` 40 | 41 | ​ 下载并安装control相关的依赖和功能包;control用于定义模型关节的类型 42 | 43 | ``` 44 | sudo apt-get install ros-humble-control-* 45 | ``` 46 | 47 | ​ 下载并安装键盘控制节点 48 | 49 | ``` 50 | sudo apt-get install ros-humble-teleop-twist-keyboard 51 | ``` 52 | 53 | 54 | 55 | ## 3. 使用方法 56 | 57 | ### 1. 创建工作空间并下载代码 58 | 59 | ​ 在终端中创建一个名为agilex_open_class的文件夹: 60 | 61 | ``` 62 | mkdir agilex_open_class 63 | ``` 64 | 65 | ​ 进入agilex_open_class文件夹 66 | 67 | ``` 68 | cd agilex_open_class 69 | ``` 70 | 71 | ​ 在创建一个src 72 | 73 | ``` 74 | mkdir src 75 | ``` 76 | 77 | ​ 进入src 78 | 79 | ``` 80 | cd src 81 | ``` 82 | 83 | ​ 下载仿真代码 84 | 85 | ``` 86 | git clone https://github.com/agilexrobotics/agilex_open_class.git 87 | ``` 88 | 89 | ​ 进入agilex_open_class文件夹 90 | 91 | ``` 92 | cd agilex_open_class 93 | ``` 94 | 95 | ​ 检查一下是否缺少依赖 96 | 97 | ``` 98 | rosdep install -i --from-path src --rosdistro humble -y 99 | ``` 100 | 101 | ​ 单独编译limo_msgs文件 102 | 103 | ``` 104 | colcon build --packages-select limo_msgs 105 | ``` 106 | 107 | ​ 在编译全部代码 108 | 109 | ``` 110 | colcon build 111 | ``` 112 | 113 | 114 | 115 | ### 2. 启动limo 模型并在Rviz中可视化 116 | 117 | ​ 进入agilex_open_class文件 118 | 119 | ``` 120 | cd agilex_open_class 121 | ``` 122 | 123 | ​ 声明工作空间的环境变量 124 | 125 | ``` 126 | source devel/setup.bash 127 | ``` 128 | 129 | ​ 声明gazebo的环境变量 130 | 131 | ``` 132 | source /usr/share/gazebo/setup.bash 133 | ``` 134 | 135 | ​ 运行指令,在Rviz中可视化模型 136 | 137 | ``` 138 | ros2 launch limo_description display_limo_diff.launch.py 139 | ``` 140 | 141 | ![](image/rviz.png) 142 | 143 | ### 3. 启动limo Gazebo仿真 144 | 145 | ​ 进入agilex_open_class文件 146 | 147 | ``` 148 | cd agilex_open_class 149 | ``` 150 | 151 | ​ 声明工作空间的环境变量 152 | 153 | ``` 154 | source devel/setup.bash 155 | ``` 156 | 157 | ​ 声明gazebo的环境变量 158 | 159 | ``` 160 | source /usr/share/gazebo/setup.bash 161 | ``` 162 | 163 | ​ 启动仿真,使用四轮差速模式 164 | 165 | ``` 166 | ros2 launch limo_gazebo_sim limo_diff_empty_world.launch.py 167 | ``` 168 | 169 | 启动键盘控制节点 170 | 171 | ``` 172 | rosrun teleop_twist_keyboard teleop_twist_keyboard.py 173 | ``` 174 | 175 | ![img](image/limo_diff.png) 176 | 177 | 178 | 179 | 180 | -------------------------------------------------------------------------------- /limo/image/limo_ackerman.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/image/limo_ackerman.png -------------------------------------------------------------------------------- /limo/image/limo_diff.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/image/limo_diff.png -------------------------------------------------------------------------------- /limo/image/rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/image/rviz.png -------------------------------------------------------------------------------- /limo/limo_bringup/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(limo_bringup) 3 | 4 | # Default to C99 5 | if(NOT CMAKE_C_STANDARD) 6 | set(CMAKE_C_STANDARD 99) 7 | endif() 8 | 9 | # Default to C++14 10 | if(NOT CMAKE_CXX_STANDARD) 11 | set(CMAKE_CXX_STANDARD 14) 12 | endif() 13 | 14 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 15 | add_compile_options(-Wall -Wextra -Wpedantic -Wno-dev) 16 | endif() 17 | 18 | # find dependencies 19 | find_package(ament_cmake REQUIRED) 20 | 21 | 22 | # if(BUILD_TESTING) 23 | # find_package(ament_lint_auto REQUIRED) 24 | # # the following line skips the linter which checks for copyrights 25 | # # uncomment the line when a copyright and license is not present in all source files 26 | # #set(ament_cmake_copyright_FOUND TRUE) 27 | # # the following line skips cpplint (only works in a git repo) 28 | # # uncomment the line when this package is not in a git repo 29 | # #set(ament_cmake_cpplint_FOUND TRUE) 30 | # ament_lint_auto_find_test_dependencies() 31 | # endif() 32 | 33 | install( 34 | DIRECTORY param maps config_files launch rviz 35 | launch DESTINATION share/${PROJECT_NAME}/ 36 | ) 37 | 38 | ament_package() -------------------------------------------------------------------------------- /limo/limo_bringup/config_files/ekf.yaml: -------------------------------------------------------------------------------- 1 | ### ekf config file ### 2 | ekf_filter_node: 3 | ros__parameters: 4 | # The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin 5 | # computation until it receives at least one message from one of theinputs. It will then run continuously at the 6 | # frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified. 7 | frequency: 50.0 8 | 9 | # ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is 10 | # set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar 11 | # environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected 12 | # by, for example, an IMU. Defaults to false if unspecified. 13 | two_d_mode: false 14 | 15 | # Whether to publish the acceleration state. Defaults to false if unspecified. 16 | publish_acceleration: false 17 | 18 | # Whether to broadcast the transformation over the /tf topic. Defaultsto true if unspecified. 19 | publish_tf: true 20 | 21 | # 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system. 22 | # 1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of odom_frame. 23 | # 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set "world_frame" 24 | # to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes. 25 | # 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates from landmark 26 | # observations) then: 27 | # 3a. Set your "world_frame" to your map_frame value 28 | # 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state estimation node 29 | # from robot_localization! However, that instance should *not* fuse the global data. 30 | # map_frame: map # Defaults to "map" if unspecified 31 | odom_frame: odom # Defaults to "odom" if unspecified 32 | base_link_frame: base_link # Defaults to "base_link" ifunspecified 33 | world_frame: odom # Defaults to the value ofodom_frame if unspecified 34 | 35 | odom0: /laser/odom 36 | odom0_config: [true, true, true, 37 | false, false, false, 38 | false, false, false, 39 | false, false, true, 40 | false, false, false] 41 | # odom1: /wheel/odom 42 | # odom1_config: [true, true, true, 43 | # false, false, false, 44 | # false, false, false, 45 | # false, false, true, 46 | # false, false, false] 47 | 48 | imu0: /imu 49 | imu0_config: [false, false, false, 50 | true, true, true, 51 | false, false, false, 52 | false, false, false, 53 | false, false, false] -------------------------------------------------------------------------------- /limo/limo_bringup/config_files/limo_laser.lua: -------------------------------------------------------------------------------- 1 | include "map_builder.lua" 2 | include "trajectory_builder.lua" 3 | 4 | options = { 5 | map_builder = MAP_BUILDER, 6 | trajectory_builder = TRAJECTORY_BUILDER, 7 | map_frame = "map", 8 | tracking_frame = "laser_link", 9 | published_frame = "laser_link", 10 | -- tracking_frame = "horizontal_laser_link", 11 | -- published_frame = "horizontal_laser_link", 12 | odom_frame = "odom", 13 | -- true改为false,不用提供里程计数据 14 | provide_odom_frame = true, 15 | -- false改为true,仅发布2D位资 16 | publish_frame_projected_to_2d = false, 17 | use_pose_extrapolator = true, 18 | -- false改为true,使用里程计数据 19 | use_odometry = false, 20 | use_nav_sat = false, 21 | use_landmarks = false, 22 | -- 0改为1,使用一个雷达 23 | num_laser_scans = 1, 24 | -- 1改为0,不使用多波雷达 25 | num_multi_echo_laser_scans = 0, 26 | -- 10改为1,1/1=1等于不分割 27 | num_subdivisions_per_laser_scan = 1, 28 | num_point_clouds = 0, 29 | lookup_transform_timeout_sec = 0.2, 30 | submap_publish_period_sec = 0.3, 31 | pose_publish_period_sec = 5e-3, 32 | trajectory_publish_period_sec = 30e-3, 33 | rangefinder_sampling_ratio = 1., 34 | odometry_sampling_ratio = 1., 35 | fixed_frame_pose_sampling_ratio = 1., 36 | imu_sampling_ratio = 1., 37 | landmarks_sampling_ratio = 1., 38 | } 39 | 40 | 41 | -- false改为true,启动2D SLAM 42 | MAP_BUILDER.use_trajectory_builder_2d = true 43 | 44 | -- 0改成0.10,比机器人半径小的都忽略 45 | TRAJECTORY_BUILDER_2D.min_range = 0.10 46 | -- 30改成3.5,限制在雷达最大扫描范围内,越小一般越精确些 47 | TRAJECTORY_BUILDER_2D.max_range = 5.5 48 | -- 5改成3,传感器数据超出有效范围最大值 49 | TRAJECTORY_BUILDER_2D.missing_data_ray_length = 3. 50 | -- true改成false,不使用IMU数据,大家可以开启,然后对比下效果 51 | TRAJECTORY_BUILDER_2D.use_imu_data = false 52 | -- false改成true,使用实时回环检测来进行前端的扫描匹配 53 | TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true 54 | -- 1.0改成0.1,提高对运动的敏感度 55 | -- TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.1) 56 | 57 | -- 0.55改成0.65,Fast csm的最低分数,高于此分数才进行优化。 58 | POSE_GRAPH.constraint_builder.min_score = 0.65 59 | --0.6改成0.7,全局定位最小分数,低于此分数则认为目前全局定位不准确 60 | POSE_GRAPH.constraint_builder.global_localization_min_score = 0.7 61 | 62 | TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1 63 | TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10. 64 | TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1 65 | 66 | POSE_GRAPH.optimization_problem.huber_scale = 1e2 67 | POSE_GRAPH.optimize_every_n_nodes = 35 68 | 69 | -- 设置0可关闭全局SLAM 70 | -- POSE_GRAPH.optimize_every_n_nodes = 0 71 | 72 | return options 73 | -------------------------------------------------------------------------------- /limo/limo_bringup/config_files/limo_lds_2d.lua: -------------------------------------------------------------------------------- 1 | include "map_builder.lua" 2 | include "trajectory_builder.lua" 3 | 4 | options = { 5 | map_builder = MAP_BUILDER, 6 | trajectory_builder = TRAJECTORY_BUILDER, 7 | map_frame = "map", 8 | tracking_frame = "base_footprint", 9 | -- base_link改为odom,发布map到odom之间的位姿态 10 | published_frame = "odom", 11 | odom_frame = "odom", 12 | -- true改为false,不用提供里程计数据 13 | provide_odom_frame = false, 14 | -- false改为true,仅发布2D位资 15 | publish_frame_projected_to_2d = true, 16 | -- false改为true,使用里程计数据 17 | use_odometry = true, 18 | use_nav_sat = false, 19 | use_landmarks = false, 20 | -- 0改为1,使用一个雷达 21 | num_laser_scans = 1, 22 | -- 1改为0,不使用多波雷达 23 | num_multi_echo_laser_scans = 0, 24 | -- 10改为1,1/1=1等于不分割 25 | num_subdivisions_per_laser_scan = 1, 26 | num_point_clouds = 0, 27 | lookup_transform_timeout_sec = 0.02, 28 | submap_publish_period_sec = 0.3, 29 | pose_publish_period_sec = 5e-3, 30 | trajectory_publish_period_sec = 30e-3, 31 | rangefinder_sampling_ratio = 1., 32 | odometry_sampling_ratio = 1., 33 | fixed_frame_pose_sampling_ratio = 1., 34 | imu_sampling_ratio = 1., 35 | landmarks_sampling_ratio = 1., 36 | } 37 | 38 | 39 | -- false改为true,启动2D SLAM 40 | MAP_BUILDER.use_trajectory_builder_2d = true 41 | 42 | -- 0改成0.10,比机器人半径小的都忽略 43 | TRAJECTORY_BUILDER_2D.min_range = 0.10 44 | -- 30改成3.5,限制在雷达最大扫描范围内,越小一般越精确些 45 | TRAJECTORY_BUILDER_2D.max_range = 3.5 46 | -- 5改成3,传感器数据超出有效范围最大值 47 | TRAJECTORY_BUILDER_2D.missing_data_ray_length = 3. 48 | -- true改成false,不使用IMU数据,大家可以开启,然后对比下效果 49 | TRAJECTORY_BUILDER_2D.use_imu_data = false 50 | -- false改成true,使用实时回环检测来进行前端的扫描匹配 51 | TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true 52 | -- 1.0改成0.1,提高对运动的敏感度 53 | TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.1) 54 | 55 | -- 0.55改成0.65,Fast csm的最低分数,高于此分数才进行优化。 56 | POSE_GRAPH.constraint_builder.min_score = 0.65 57 | --0.6改成0.7,全局定位最小分数,低于此分数则认为目前全局定位不准确 58 | POSE_GRAPH.constraint_builder.global_localization_min_score = 0.7 59 | 60 | TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1 61 | TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10. 62 | TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1 63 | 64 | POSE_GRAPH.optimization_problem.huber_scale = 1e2 65 | POSE_GRAPH.optimize_every_n_nodes = 35 66 | -- 设置0可关闭全局SLAM 67 | -- POSE_GRAPH.optimize_every_n_nodes = 0 68 | 69 | return options 70 | -------------------------------------------------------------------------------- /limo/limo_bringup/config_files/slam_box.yaml: -------------------------------------------------------------------------------- 1 | slam_toolbox: 2 | ros__parameters: 3 | 4 | # Plugin params 5 | solver_plugin: solver_plugins::CeresSolver 6 | ceres_linear_solver: SPARSE_NORMAL_CHOLESKY 7 | ceres_preconditioner: SCHUR_JACOBI 8 | ceres_trust_strategy: LEVENBERG_MARQUARDT 9 | ceres_dogleg_type: TRADITIONAL_DOGLEG 10 | ceres_loss_function: None 11 | 12 | # ROS Parameters 13 | odom_frame: odom 14 | map_frame: map 15 | base_frame: base_footprint 16 | scan_topic: /scan 17 | mode: mapping #localization 18 | 19 | # if you'd like to immediately start continuing a map at a given pose 20 | # or at the dock, but they are mutually exclusive, if pose is given 21 | # will use pose 22 | #map_file_name: test_steve 23 | #map_start_pose: [0.0, 0.0, 0.0] 24 | #map_start_at_dock: true 25 | 26 | debug_logging: false 27 | throttle_scans: 1 28 | transform_publish_period: 0.02 #if 0 never publishes odometry 29 | map_update_interval: 1.0 30 | resolution: 0.05 31 | max_laser_range: 50.0 #for rastering images 32 | minimum_time_interval: 0.5 33 | transform_timeout: 0.2 34 | tf_buffer_duration: 30. 35 | stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps 36 | enable_interactive_mode: true 37 | 38 | # General Parameters 39 | use_scan_matching: true 40 | use_scan_barycenter: true 41 | minimum_travel_distance: 0.5 42 | minimum_travel_heading: 0.5 43 | scan_buffer_size: 10 44 | scan_buffer_maximum_scan_distance: 10.0 45 | link_match_minimum_response_fine: 0.1 46 | link_scan_maximum_distance: 1.5 47 | loop_search_maximum_distance: 3.0 48 | do_loop_closing: true 49 | loop_match_minimum_chain_size: 10 50 | loop_match_maximum_variance_coarse: 3.0 51 | loop_match_minimum_response_coarse: 0.35 52 | loop_match_minimum_response_fine: 0.45 53 | 54 | # Correlation Parameters - Correlation Parameters 55 | correlation_search_space_dimension: 0.5 56 | correlation_search_space_resolution: 0.01 57 | correlation_search_space_smear_deviation: 0.1 58 | 59 | # Correlation Parameters - Loop Closure Parameters 60 | loop_search_space_dimension: 8.0 61 | loop_search_space_resolution: 0.05 62 | loop_search_space_smear_deviation: 0.03 63 | 64 | # Scan Matcher Parameters 65 | distance_variance_penalty: 0.5 66 | angle_variance_penalty: 1.0 67 | 68 | fine_search_angle_offset: 0.00349 69 | coarse_search_angle_offset: 0.349 70 | coarse_angle_resolution: 0.0349 71 | minimum_angle_penalty: 0.9 72 | minimum_distance_penalty: 0.5 73 | use_response_expansion: true -------------------------------------------------------------------------------- /limo/limo_bringup/launch/__pycache__/cartographer.launch.cpython-310.pyc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/launch/__pycache__/cartographer.launch.cpython-310.pyc -------------------------------------------------------------------------------- /limo/limo_bringup/launch/__pycache__/occupancy_grid.launch.cpython-310.pyc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/launch/__pycache__/occupancy_grid.launch.cpython-310.pyc -------------------------------------------------------------------------------- /limo/limo_bringup/launch/humble/__pycache__/limo_rtab_nav2.laun.cpython-310.pyc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/launch/humble/__pycache__/limo_rtab_nav2.laun.cpython-310.pyc -------------------------------------------------------------------------------- /limo/limo_bringup/launch/humble/ekf_odom.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | import launch 3 | import launch_ros 4 | 5 | 6 | def generate_launch_description(): 7 | package_name = 'limo_bringup' 8 | 9 | ld = launch.LaunchDescription() 10 | pkg_share = launch_ros.substitutions.FindPackageShare(package=package_name).find(package_name) 11 | 12 | robot_localization_node = launch_ros.actions.Node( 13 | package='robot_localization', 14 | executable='ekf_node', 15 | name='ekf_filter_node', 16 | output='screen', 17 | parameters=[os.path.join(pkg_share, 'config_files/ekf.yaml'), {'use_sim_time': launch.substitutions.LaunchConfiguration('use_sim_time')}] 18 | ) 19 | 20 | 21 | ld.add_action(launch.actions.DeclareLaunchArgument(name='use_sim_time', default_value='False', 22 | description='Flag to enable use_sim_time')) 23 | ld.add_action(robot_localization_node) 24 | return ld -------------------------------------------------------------------------------- /limo/limo_bringup/launch/humble/limo_cartographer.launch copy.py: -------------------------------------------------------------------------------- 1 | from launch import LaunchDescription 2 | from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription 3 | from launch.conditions import IfCondition, UnlessCondition 4 | from launch.substitutions import LaunchConfiguration 5 | from launch_ros.actions import Node, SetRemap 6 | from launch_ros.substitutions import FindPackageShare 7 | from launch.launch_description_sources import PythonLaunchDescriptionSource 8 | from ament_index_python.packages import get_package_share_directory 9 | import os 10 | 11 | def generate_launch_description(): 12 | 13 | ## ***** Launch arguments ***** 14 | # 是否使用仿真时间,真实的机器人我们不需要,设置为False 15 | use_sim_time_arg = LaunchConfiguration('use_sim_time', default='False') 16 | rviz2_config = os.path.join(get_package_share_directory('limo_bringup'),'rviz','cartographer.rviz') 17 | ## ***** File paths ****** 18 | # 找到cartographer功能包的地址 19 | pkg_share = FindPackageShare('cartographer_ros').find('cartographer_ros') 20 | # 地图的分辨率 21 | resolution = LaunchConfiguration('resolution', default='0.05') 22 | # 地图的发布周期 23 | publish_period_sec = LaunchConfiguration('publish_period_sec', default='1.0') 24 | cartographer_node = Node( 25 | package = 'cartographer_ros', 26 | executable = 'cartographer_node', 27 | parameters = [{'use_sim_time': use_sim_time_arg}], 28 | arguments = [ 29 | '-configuration_directory', FindPackageShare('limo_bringup').find('limo_bringup') + '/config_files', 30 | '-configuration_basename', 'limo_lds_2d.lua'], 31 | remappings = [ 32 | ('echoes', 'horizontal_laser_2d')], 33 | output = 'screen' 34 | ) 35 | 36 | # 可视化节点 37 | rviz_node = Node( 38 | package='rviz2', 39 | namespace='rviz2', 40 | executable='rviz2', 41 | name='rviz2', 42 | arguments=['-d',rviz2_config], 43 | parameters=[{'use_sim_time': use_sim_time_arg}], 44 | output='screen') 45 | 46 | cartographer_occupancy_grid_node = Node( 47 | package = 'cartographer_ros', 48 | executable = 'cartographer_occupancy_grid_node', 49 | parameters = [{'use_sim_time': use_sim_time_arg}], 50 | arguments=['-resolution', resolution, '-publish_period_sec', publish_period_sec]) 51 | 52 | return LaunchDescription([ 53 | # Nodes 54 | rviz_node , 55 | cartographer_node, 56 | cartographer_occupancy_grid_node, 57 | # laser_to_map_tf_node, 58 | ]) 59 | 60 | 61 | -------------------------------------------------------------------------------- /limo/limo_bringup/launch/humble/limo_cartographer.launch.py: -------------------------------------------------------------------------------- 1 | 2 | import os 3 | from launch import LaunchDescription 4 | from launch.substitutions import LaunchConfiguration 5 | from launch_ros.actions import Node 6 | from launch_ros.substitutions import FindPackageShare 7 | from ament_index_python.packages import get_package_share_directory 8 | 9 | 10 | def generate_launch_description(): 11 | # 定位到功能包的地址 12 | pkg_share = FindPackageShare(package='limo_bringup').find('limo_bringup') 13 | rviz_config_dir = os.path.join(get_package_share_directory('limo_bringup'),'rviz','cartographer.rviz') 14 | #=====================运行节点需要的配置======================================================================= 15 | # 是否使用仿真时间,我们用gazebo,这里设置成true 16 | use_sim_time = LaunchConfiguration('use_sim_time', default='true') 17 | # 地图的分辨率 18 | resolution = LaunchConfiguration('resolution', default='0.05') 19 | # 地图的发布周期 20 | publish_period_sec = LaunchConfiguration('publish_period_sec', default='1.0') 21 | # 配置文件夹路径 22 | configuration_directory = LaunchConfiguration('configuration_directory',default= os.path.join(pkg_share, 'config_files') ) 23 | # 配置文件 24 | configuration_basename = LaunchConfiguration('configuration_basename', default='limo_lds_2d.lua') 25 | 26 | 27 | 28 | #=====================声明三个节点,cartographer/occupancy_grid_node/rviz_node================================= 29 | cartographer_node = Node( 30 | package='cartographer_ros', 31 | executable='cartographer_node', 32 | name='cartographer_node', 33 | output='screen', 34 | parameters=[{'use_sim_time': use_sim_time}], 35 | arguments=['-configuration_directory', configuration_directory, 36 | '-configuration_basename', configuration_basename], 37 | ) 38 | 39 | cartographer_occupancy_grid_node = Node( 40 | package='cartographer_ros', 41 | executable='cartographer_occupancy_grid_node', 42 | name='cartographer_occupancy_grid_node', 43 | output='screen', 44 | parameters=[{'use_sim_time': use_sim_time}], 45 | arguments=['-resolution', resolution, '-publish_period_sec', publish_period_sec], 46 | ) 47 | 48 | rviz_node = Node( 49 | package='rviz2', 50 | executable='rviz2', 51 | name='rviz2', 52 | arguments=['-d', rviz_config_dir], 53 | parameters=[{'use_sim_time': use_sim_time}], 54 | output='screen') 55 | 56 | #===============================================定义启动文件======================================================== 57 | ld = LaunchDescription() 58 | ld.add_action(cartographer_node) 59 | ld.add_action(cartographer_occupancy_grid_node) 60 | ld.add_action(rviz_node) 61 | 62 | return ld 63 | -------------------------------------------------------------------------------- /limo/limo_bringup/launch/humble/limo_nav2.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | 3 | from ament_index_python.packages import get_package_share_directory 4 | from launch import LaunchDescription 5 | from launch.actions import DeclareLaunchArgument 6 | from launch.actions import IncludeLaunchDescription 7 | from launch.launch_description_sources import PythonLaunchDescriptionSource 8 | from launch.substitutions import LaunchConfiguration 9 | from launch_ros.actions import Node 10 | 11 | 12 | def generate_launch_description(): 13 | limo_bringup_dir = get_package_share_directory('limo_bringup') 14 | nav2_bringup_dir = get_package_share_directory('nav2_bringup') 15 | 16 | use_sim_time = LaunchConfiguration('use_sim_time', default='true') 17 | map_yaml_path = LaunchConfiguration('map',default=os.path.join(limo_bringup_dir,'maps','map04.yaml')) 18 | nav2_param_path = LaunchConfiguration('params_file',default=os.path.join(limo_bringup_dir,'param','nav2.yaml')) 19 | 20 | rviz_config_dir = os.path.join(nav2_bringup_dir,'rviz','nav2_default_view.rviz') 21 | 22 | return LaunchDescription([ 23 | DeclareLaunchArgument('use_sim_time',default_value=use_sim_time,description='Use simulation (Gazebo) clock if true'), 24 | DeclareLaunchArgument('map',default_value=map_yaml_path,description='Full path to map file to load'), 25 | DeclareLaunchArgument('params_file',default_value=nav2_param_path,description='Full path to param file to load'), 26 | 27 | IncludeLaunchDescription( 28 | PythonLaunchDescriptionSource([nav2_bringup_dir,'/launch','/bringup_launch.py']), 29 | launch_arguments={ 30 | 'map': map_yaml_path, 31 | 'use_sim_time': use_sim_time, 32 | 'params_file': nav2_param_path}.items(), 33 | ), 34 | 35 | Node( 36 | package='rviz2', 37 | executable='rviz2', 38 | name='rviz2', 39 | arguments=['-d', rviz_config_dir], 40 | parameters=[{'use_sim_time': use_sim_time}], 41 | output='screen'), 42 | ]) 43 | -------------------------------------------------------------------------------- /limo/limo_bringup/launch/humble/limo_nav2_explore.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | 3 | from ament_index_python.packages import get_package_share_directory 4 | from launch import LaunchDescription 5 | from launch.actions import DeclareLaunchArgument 6 | from launch.actions import IncludeLaunchDescription 7 | from launch.launch_description_sources import PythonLaunchDescriptionSource 8 | from launch.substitutions import LaunchConfiguration 9 | from launch_ros.actions import Node 10 | 11 | 12 | def generate_launch_description(): 13 | limo_bringup_dir = get_package_share_directory('limo_bringup') 14 | nav2_bringup_dir = get_package_share_directory('nav2_bringup') 15 | 16 | use_sim_time = LaunchConfiguration('use_sim_time', default='true') 17 | # map_yaml_path = LaunchConfiguration('map',default=os.path.join(limo_bringup_dir,'maps','map04.yaml')) 18 | nav2_param_path = LaunchConfiguration('params_file',default=os.path.join(limo_bringup_dir,'param','nav2_explore.yaml')) 19 | 20 | rviz_config_dir = os.path.join(nav2_bringup_dir,'rviz','nav2_default_view.rviz') 21 | 22 | return LaunchDescription([ 23 | DeclareLaunchArgument('use_sim_time',default_value=use_sim_time,description='Use simulation (Gazebo) clock if true'), 24 | # DeclareLaunchArgument('map',default_value=map_yaml_path,description='Full path to map file to load'), 25 | DeclareLaunchArgument('params_file',default_value=nav2_param_path,description='Full path to param file to load'), 26 | 27 | IncludeLaunchDescription( 28 | PythonLaunchDescriptionSource([nav2_bringup_dir,'/launch','/navigation_launch.py']), 29 | launch_arguments={ 30 | # 'map': map_yaml_path, 31 | 'use_sim_time': use_sim_time, 32 | 'params_file': nav2_param_path}.items(), 33 | ), 34 | 35 | Node( 36 | package='rviz2', 37 | executable='rviz2', 38 | name='rviz2', 39 | arguments=['-d', rviz_config_dir], 40 | parameters=[{'use_sim_time': use_sim_time}], 41 | output='screen'), 42 | ]) 43 | -------------------------------------------------------------------------------- /limo/limo_bringup/launch/humble/limo_rtab_nav2.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | 3 | from ament_index_python.packages import get_package_share_directory 4 | from launch import LaunchDescription 5 | from launch.actions import DeclareLaunchArgument 6 | from launch.actions import IncludeLaunchDescription 7 | from launch.launch_description_sources import PythonLaunchDescriptionSource 8 | from launch.substitutions import LaunchConfiguration 9 | from launch_ros.actions import Node 10 | 11 | 12 | def generate_launch_description(): 13 | limo_bringup_dir = get_package_share_directory('limo_bringup') 14 | nav2_bringup_dir = get_package_share_directory('nav2_bringup') 15 | 16 | use_sim_time = LaunchConfiguration('use_sim_time', default='false') 17 | map_yaml_path = LaunchConfiguration('map',default=os.path.join(limo_bringup_dir,'maps','map01.yaml')) 18 | nav2_param_path = LaunchConfiguration('params_file',default=os.path.join(limo_bringup_dir,'param','nav2_ackermann_rtab.yaml')) 19 | 20 | rviz_config_dir = os.path.join(limo_bringup_dir,'rviz','nav2_rtab.rviz') 21 | 22 | return LaunchDescription([ 23 | DeclareLaunchArgument('use_sim_time',default_value=use_sim_time,description='Use simulation (Gazebo) clock if true'), 24 | DeclareLaunchArgument('map',default_value=map_yaml_path,description='Full path to map file to load'), 25 | DeclareLaunchArgument('params_file',default_value=nav2_param_path,description='Full path to param file to load'), 26 | 27 | IncludeLaunchDescription( 28 | PythonLaunchDescriptionSource([nav2_bringup_dir,'/launch','/navigation_launch.py']), 29 | launch_arguments={ 30 | # 'map': map_yaml_path, 31 | 'use_sim_time': use_sim_time, 32 | 'params_file': nav2_param_path}.items(), 33 | ), 34 | 35 | Node( 36 | package='rviz2', 37 | executable='rviz2', 38 | name='rviz2', 39 | arguments=['-d', rviz_config_dir], 40 | parameters=[{'use_sim_time': use_sim_time}], 41 | output='screen'), 42 | ]) 43 | -------------------------------------------------------------------------------- /limo/limo_bringup/launch/humble/limo_rtab_rgbd.launch.py: -------------------------------------------------------------------------------- 1 | from launch import LaunchDescription 2 | from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable 3 | from launch.substitutions import LaunchConfiguration 4 | from launch.conditions import IfCondition, UnlessCondition 5 | from launch_ros.actions import Node 6 | 7 | def generate_launch_description(): 8 | 9 | use_sim_time = LaunchConfiguration('use_sim_time') 10 | qos = LaunchConfiguration('qos') 11 | localization = LaunchConfiguration('localization') 12 | 13 | parameters={ 14 | 'frame_id':'base_link', 15 | 'use_sim_time':True, 16 | 'subscribe_depth':True, 17 | 'subscribe_rgbd':False, 18 | 'subscribe_rgb':True, 19 | 'subscribe_scan':True, 20 | 'use_action_for_goal':True, 21 | 'wait_for_transform':0.2, 22 | 'qos_image':qos, 23 | 'qos_scan':qos, 24 | 'qos_camera_info':qos, 25 | 'approx_sync':True, 26 | 'Reg/Force3DoF':'true', 27 | 'Optimizer/GravitySigma':'0' # Disable imu constraints (we are already in 2D) 28 | } 29 | 30 | remappings=[ 31 | ('odom','/odom'), 32 | ('scan','/scan'), 33 | ('rgb/image', '/limo/limo/image_raw'), 34 | ('rgb/camera_info', '/limo/limo/camera_info'), 35 | ('depth/image', '/limo/limo/depth/image_raw')] 36 | # base_link_to_camera_node = Node( 37 | # package='tf2_ros', 38 | # executable='static_transform_publisher', 39 | # name='base_link_to_base_camera', 40 | # arguments=['0.1','0','0.18','0','0','0','1','base_link','camera_link'] 41 | # ) 42 | return LaunchDescription([ 43 | 44 | # Launch arguments 45 | DeclareLaunchArgument( 46 | 'use_sim_time', default_value='false', 47 | description='Use simulation (Gazebo) clock if true'), 48 | 49 | DeclareLaunchArgument( 50 | 'qos', default_value='2', 51 | description='QoS used for input sensor topics'), 52 | 53 | DeclareLaunchArgument( 54 | 'localization', default_value='false', 55 | description='Launch in localization mode.'), 56 | 57 | # Nodes to launch 58 | 59 | # SLAM mode: 60 | Node( 61 | condition=UnlessCondition(localization), 62 | package='rtabmap_slam', executable='rtabmap', output='screen', 63 | parameters=[parameters], 64 | remappings=remappings, 65 | arguments=['-d']), # This will delete the previous database (~/.ros/rtabmap.db) 66 | 67 | # Localization mode: 68 | Node( 69 | condition=IfCondition(localization), 70 | package='rtabmap_slam', executable='rtabmap', output='screen', 71 | parameters=[parameters, 72 | {'Mem/IncrementalMemory':'False', 73 | 'Mem/InitWMWithAllNodes':'True'}], 74 | remappings=remappings), 75 | 76 | Node( 77 | package='rtabmap_viz', executable='rtabmap_viz', output='screen', 78 | parameters=[parameters], 79 | remappings=remappings), 80 | # base_link_to_camera_node 81 | ]) 82 | -------------------------------------------------------------------------------- /limo/limo_bringup/launch/humble/limo_slam_box.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | from ament_index_python.packages import get_package_share_directory 3 | 4 | from launch import LaunchDescription 5 | from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable, IncludeLaunchDescription 6 | from launch.substitutions import LaunchConfiguration 7 | from launch_ros.actions import Node 8 | from ament_index_python.packages import get_package_share_directory 9 | from launch.launch_description_sources import PythonLaunchDescriptionSource 10 | 11 | 12 | def generate_launch_description(): 13 | use_sim_time = LaunchConfiguration('use_sim_time',default='true') 14 | slam_params_file = LaunchConfiguration('slam_params_file') 15 | rviz_config_dir = os.path.join( 16 | get_package_share_directory('limo_bringup'), 17 | 'rviz', 18 | 'slam_toolbox.rviz') 19 | 20 | return LaunchDescription([ 21 | # Node( 22 | # package='rf2o_laser_odometry', 23 | # executable='rf2o_laser_odometry_node', 24 | # name='rf2o_laser_odometry', 25 | # output='screen', 26 | # parameters=[{ 27 | # 'laser_scan_topic' : '/scan', 28 | # 'odom_topic' : '/odom', 29 | # 'publish_tf' : True, 30 | # 'base_frame_id' : 'base_link', 31 | # 'odom_frame_id' : 'odom', 32 | # 'init_pose_from_topic' : '', 33 | # 'freq' : 20.0}],), 34 | DeclareLaunchArgument( 35 | 'use_sim_time', 36 | default_value='true', 37 | description='Use simulation/Gazebo clock'), 38 | 39 | DeclareLaunchArgument( 40 | 'slam_params_file', 41 | default_value=os.path.join(get_package_share_directory("limo_bringup"), 42 | 'config_files', 'slam_box.yaml'), 43 | description='Full path to the ROS2 parameters file to use for the slam_toolbox node'), 44 | Node( 45 | parameters=[ 46 | slam_params_file, 47 | {'use_sim_time': use_sim_time} 48 | ], 49 | package='slam_toolbox', 50 | executable='sync_slam_toolbox_node', 51 | name='slam_toolbox', 52 | output='screen'), 53 | 54 | Node( 55 | package='rviz2', 56 | executable='rviz2', 57 | name='rviz2', 58 | arguments=['-d', rviz_config_dir], 59 | parameters=[{'use_sim_time': use_sim_time}], 60 | output='screen'), 61 | ]) -------------------------------------------------------------------------------- /limo/limo_bringup/launch/humble/limo_start.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | 3 | from ament_index_python.packages import get_package_share_directory 4 | from launch import LaunchDescription 5 | from launch.actions import DeclareLaunchArgument 6 | from launch.actions import IncludeLaunchDescription 7 | from launch.launch_description_sources import PythonLaunchDescriptionSource 8 | from launch.substitutions import LaunchConfiguration 9 | from launch_ros.actions import Node 10 | 11 | def generate_launch_description(): 12 | rf2o_dir = get_package_share_directory('rf2o_laser_odometry') 13 | ydlidar_ros_dir = get_package_share_directory("ydlidar_ros2_driver") 14 | limo_base_dir = get_package_share_directory('limo_base') 15 | limo_bringup_dir = get_package_share_directory('limo_bringup') 16 | limo_gazebo = get_package_share_directory('limo_car') 17 | 18 | 19 | pub_tf=Node( 20 | package="limo_base", 21 | executable="tf_pub", 22 | output='screen', 23 | name='tf_pub_node', 24 | ) 25 | base_link_to_laser_tf_node = Node( 26 | package='tf2_ros', 27 | executable='static_transform_publisher', 28 | name='base_link_to_base_laser_ydlidar', 29 | arguments=['0','0','0.18','0','0','0','1','base_link','laser_link'] 30 | ) 31 | 32 | return LaunchDescription([ 33 | IncludeLaunchDescription( 34 | PythonLaunchDescriptionSource([limo_base_dir,'/launch','/limo_base.launch.py']), 35 | ), 36 | IncludeLaunchDescription( 37 | PythonLaunchDescriptionSource([rf2o_dir,'/launch','/rf2o_laser_odometry.launch.py']), 38 | ), 39 | IncludeLaunchDescription( 40 | PythonLaunchDescriptionSource([ydlidar_ros_dir,'/launch','/ydlidar.launch.py']), 41 | ), 42 | # IncludeLaunchDescription( 43 | # PythonLaunchDescriptionSource([limo_bringup_dir,'/launch/humble','/ekf_odom.launch.py']), 44 | # ), 45 | # pub_tf 46 | base_link_to_laser_tf_node 47 | ]) 48 | -------------------------------------------------------------------------------- /limo/limo_bringup/launch/humble/rgbdslam_datasets.launch.py: -------------------------------------------------------------------------------- 1 | 2 | # Example to run rgbd datasets: 3 | # [ROS1] Prepare ROS1 rosbag for conversion to ROS2 4 | # $ wget http://vision.in.tum.de/rgbd/dataset/freiburg3/rgbd_dataset_freiburg3_long_office_household.bag 5 | # $ rosbag decompress rgbd_dataset_freiburg3_long_office_household.bag 6 | # $ wget https://raw.githubusercontent.com/srv/srv_tools/kinetic/bag_tools/scripts/change_frame_id.py 7 | # Edit change_frame_id.py, remove/comment lines beginning with "PKG" and "import roslib", change line "Exception, e" to "Exception" 8 | # $ roscore 9 | # $ python3 change_frame_id.py -o rgbd_dataset_freiburg3_long_office_household_frameid_fixed.bag -i rgbd_dataset_freiburg3_long_office_household.bag -f openni_rgb_optical_frame -t /camera/rgb/image_color 10 | # [ROS2] 11 | # $ sudo pip install rosbags # See https://docs.openvins.com/dev-ros1-to-ros2.html 12 | # $ rosbags-convert rgbd_dataset_freiburg3_long_office_household_frameid_fixed.bag 13 | 14 | # $ ros2 launch rtabmap_ros rgbdslam_datasets.launch.py 15 | # $ cd rgbd_dataset_freiburg3_long_office_household_frameid_fixed 16 | # $ ros2 bag play rgbd_dataset_freiburg3_long_office_household_frameid_fixed.db3 --clock 17 | 18 | 19 | from launch import LaunchDescription 20 | from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable 21 | from launch.substitutions import LaunchConfiguration 22 | from launch_ros.actions import Node 23 | from launch_ros.actions import SetParameter 24 | 25 | def generate_launch_description(): 26 | 27 | parameters=[{ 28 | 'frame_id':'camera_link', 29 | 'subscribe_depth':True, 30 | 'subscribe_odom_info':False, 31 | # RTAB-Map's parameters should all be string type: 32 | 'Odom/Strategy':'0', 33 | 'Odom/ResetCountdown':'15', 34 | 'Odom/GuessSmoothingDelay':'0', 35 | 'Rtabmap/StartNewMapOnLoopClosure':'true', 36 | 'RGBD/CreateOccupancyGrid':'false', 37 | 'Rtabmap/CreateIntermediateNodes':'true', 38 | 'RGBD/LinearUpdate':'0', 39 | 'RGBD/AngularUpdate':'0'}] 40 | 41 | remappings=[ 42 | ('rgb/image', '/camera/color/image_raw'), 43 | ('rgb/camera_info', '/camera/color/camera_info'), 44 | ('depth/image', '/camera/depth/image_raw')] 45 | 46 | 47 | return LaunchDescription([ 48 | 49 | SetParameter(name='use_sim_time', value=False), 50 | # 'use_sim_time' will be set on all nodes following the line above 51 | 52 | # Nodes to launch 53 | Node( 54 | package='rtabmap_ros', executable='rgbd_odometry', output='screen', 55 | parameters=parameters, 56 | remappings=remappings), 57 | 58 | Node( 59 | package='rtabmap_ros', executable='rtabmap', output='screen', 60 | parameters=parameters, 61 | remappings=remappings, 62 | arguments=['-d']), 63 | 64 | Node( 65 | package='rtabmap_ros', executable='rtabmapviz', output='screen', 66 | parameters=parameters, 67 | remappings=remappings), 68 | 69 | # /tf topic is missing in the converted ROS2 bag, create a fake tf 70 | Node( 71 | package='tf2_ros', executable='static_transform_publisher', output='screen', 72 | arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'camera_link', 'openni_rgb_optical_frame']), 73 | ]) 74 | -------------------------------------------------------------------------------- /limo/limo_bringup/maps/limo.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/maps/limo.pgm -------------------------------------------------------------------------------- /limo/limo_bringup/maps/limo.yaml: -------------------------------------------------------------------------------- 1 | image: limo.pgm 2 | mode: trinary 3 | resolution: 0.05 4 | origin: [-3.09, -7.29, 0] 5 | negate: 0 6 | occupied_thresh: 0.65 7 | free_thresh: 0.169 -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/maps/map.pgm -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map.yaml: -------------------------------------------------------------------------------- 1 | image: map.pgm 2 | mode: trinary 3 | resolution: 0.05 4 | origin: [-6.09, -7.2, 0] 5 | negate: 0 6 | occupied_thresh: 0.65 7 | free_thresh: 0.25 -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map01.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/maps/map01.pgm -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map01.yaml: -------------------------------------------------------------------------------- 1 | image: map01.pgm 2 | mode: trinary 3 | resolution: 0.05 4 | origin: [-3.6, -7.84, 0] 5 | negate: 0 6 | occupied_thresh: 0.65 7 | free_thresh: 0.25 -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map02.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/maps/map02.pgm -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map02.yaml: -------------------------------------------------------------------------------- 1 | image: map02.pgm 2 | mode: trinary 3 | resolution: 0.05 4 | origin: [-1.3, -3.67, 0] 5 | negate: 0 6 | occupied_thresh: 0.65 7 | free_thresh: 0.25 -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map03.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/maps/map03.pgm -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map03.yaml: -------------------------------------------------------------------------------- 1 | image: map03.pgm 2 | mode: trinary 3 | resolution: 0.05 4 | origin: [-0.806, -8.2, 0] 5 | negate: 0 6 | occupied_thresh: 0.65 7 | free_thresh: 0.25 -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map04.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/maps/map04.pgm -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map04.yaml: -------------------------------------------------------------------------------- 1 | image: map04.pgm 2 | mode: trinary 3 | resolution: 0.05 4 | origin: [-6.2, -2.78, 0] 5 | negate: 0 6 | occupied_thresh: 0.65 7 | free_thresh: 0.25 -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map212.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/maps/map212.pgm -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map212.yaml: -------------------------------------------------------------------------------- 1 | image: map212.pgm 2 | mode: trinary 3 | resolution: 0.05 4 | origin: [-5.87, -2.33, 0] 5 | negate: 0 6 | occupied_thresh: 0.65 7 | free_thresh: 0.25 -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map222 (copy).pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/maps/map222 (copy).pgm -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map222.pgm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_bringup/maps/map222.pgm -------------------------------------------------------------------------------- /limo/limo_bringup/maps/map222.yaml: -------------------------------------------------------------------------------- 1 | image: map222.pgm 2 | mode: trinary 3 | resolution: 0.05 4 | origin: [-6.65, -3.02, 0] 5 | negate: 0 6 | occupied_thresh: 0.65 7 | free_thresh: 0.25 -------------------------------------------------------------------------------- /limo/limo_bringup/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | limo_bringup 4 | 0.0.0 5 | The limo_bringup package 6 | 7 | 8 | 9 | 10 | qie 11 | TODO: License declaration 12 | 13 | ament_cmake 14 | 15 | rclcpp 16 | std_msgs 17 | nav_msgs 18 | geometry_msgs 19 | sensor_msgs 20 | limo_msgs 21 | tf2 22 | tf2_ros 23 | 24 | nav2_amcl 25 | nav2_lifecycle_manager 26 | nav2_map_server 27 | nav2_controller 28 | nav2_planner 29 | nav2_recoveries 30 | nav2_bt_navigator 31 | nav2_waypoint_follower 32 | cartographer_ros 33 | cartographer 34 | teleop_twist_keyboard 35 | 36 | 37 | ament_lint_auto 38 | ament_lint_common 39 | 40 | 41 | ament_cmake 42 | 43 | 44 | 45 | -------------------------------------------------------------------------------- /limo/limo_bringup/param/costmap_common.yaml: -------------------------------------------------------------------------------- 1 | footprint: [[-0.16, -0.11], [-0.16, 0.11], [0.16, 0.11], [0.16, -0.11]] 2 | footprint_padding: 0.02 3 | 4 | robot_base_frame: base_link 5 | update_frequency: 4.0 6 | publish_frequency: 3.0 7 | transform_tolerance: 0.5 8 | publish_voxel_map: true 9 | 10 | resolution: 0.05 11 | 12 | obstacle_range: 5.5 13 | raytrace_range: 6.0 14 | 15 | #layer definitions 16 | static: 17 | map_topic: /map 18 | subscribe_to_updates: true 19 | 20 | obstacles_laser: 21 | observation_sources: scan 22 | scan: {sensor_frame: laser_frame, data_type: LaserScan, clearing: true, marking: true, topic: scan, inf_is_valid: true} 23 | 24 | inflation: 25 | inflation_radius: 0.2 26 | -------------------------------------------------------------------------------- /limo/limo_bringup/param/costmap_global_laser.yaml: -------------------------------------------------------------------------------- 1 | global_frame: odom 2 | rolling_window: true 3 | track_unknown_space: true 4 | 5 | plugins: 6 | - {name: obstacles_laser, type: "costmap_2d::ObstacleLayer"} 7 | - {name: inflation, type: "costmap_2d::InflationLayer"} -------------------------------------------------------------------------------- /limo/limo_bringup/param/costmap_global_static.yaml: -------------------------------------------------------------------------------- 1 | global_frame: map 2 | rolling_window: false 3 | track_unknown_space: true 4 | 5 | plugins: 6 | - {name: static, type: "costmap_2d::StaticLayer"} 7 | - {name: inflation, type: "costmap_2d::InflationLayer"} -------------------------------------------------------------------------------- /limo/limo_bringup/param/costmap_local.yaml: -------------------------------------------------------------------------------- 1 | global_frame: odom 2 | rolling_window: true 3 | track_unknown_space: true 4 | 5 | static_map: false 6 | 7 | plugins: 8 | - {name: obstacles_laser, type: "costmap_2d::ObstacleLayer"} 9 | - {name: inflation, type: "costmap_2d::InflationLayer"} -------------------------------------------------------------------------------- /limo/limo_bringup/param/planner.yaml: -------------------------------------------------------------------------------- 1 | controller_frequency: 5.0 2 | recovery_behaviour_enabled: true 3 | 4 | NavfnROS: 5 | allow_unknown: true # Specifies whether or not to allow navfn to create plans that traverse unknown space. 6 | default_tolerance: 0.1 # A tolerance on the goal point for the planner. 7 | 8 | TrajectoryPlannerROS: 9 | # Robot Configuration Parameters 10 | acc_lim_x: 2.5 11 | acc_lim_theta: 3.2 12 | 13 | max_vel_x: 1.0 14 | min_vel_x: 0.0 15 | 16 | max_vel_theta: 1.0 17 | min_vel_theta: -1.0 18 | min_in_place_vel_theta: 0.2 19 | 20 | holonomic_robot: false 21 | escape_vel: -0.1 22 | 23 | # Goal Tolerance Parameters 24 | yaw_goal_tolerance: 0.2 25 | xy_goal_tolerance: 0.2 26 | latch_xy_goal_tolerance: false 27 | 28 | # Forward Simulation Parameters 29 | sim_time: 2.0 30 | sim_granularity: 0.02 31 | angular_sim_granularity: 0.02 32 | vx_samples: 6 33 | vtheta_samples: 20 34 | controller_frequency: 20.0 35 | 36 | # Trajectory scoring parameters 37 | meter_scoring: true # Whether the gdist_scale and pdist_scale parameters should assume that goal_distance and path_distance are expressed in units of meters or cells. Cells are assumed by default (false). 38 | occdist_scale: 0.1 #The weighting for how much the controller should attempt to avoid obstacles. default 0.01 39 | pdist_scale: 0.75 # The weighting for how much the controller should stay close to the path it was given . default 0.6 40 | gdist_scale: 1.0 # The weighting for how much the controller should attempt to reach its local goal, also controls speed default 0.8 41 | 42 | heading_lookahead: 0.325 #How far to look ahead in meters when scoring different in-place-rotation trajectories 43 | heading_scoring: false #Whether to score based on the robot's heading to the path or its distance from the path. default false 44 | heading_scoring_timestep: 0.8 #How far to look ahead in time in seconds along the simulated trajectory when using heading scoring (double, default: 0.8) 45 | dwa: true #Whether to use the Dynamic Window Approach (DWA)_ or whether to use Trajectory Rollout 46 | simple_attractor: false 47 | publish_cost_grid_pc: true 48 | 49 | # Oscillation Prevention Parameters 50 | oscillation_reset_dist: 0.25 #How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05) 51 | escape_reset_dist: 0.1 52 | escape_reset_theta: 0.1 53 | 54 | DWAPlannerROS: 55 | # Robot configuration parameters 56 | acc_lim_x: 2.5 57 | acc_lim_y: 0 58 | acc_lim_th: 3.2 59 | 60 | max_vel_x: 0.5 61 | min_vel_x: 0.0 62 | max_vel_y: 0 63 | min_vel_y: 0 64 | 65 | max_vel_trans: 0.5 66 | min_vel_trans: 0.1 67 | max_vel_theta: 1.0 68 | min_vel_theta: 0.2 69 | 70 | # Goal Tolerance Parameters 71 | yaw_goal_tolerance: 0.2 72 | xy_goal_tolerance: 0.25 73 | latch_xy_goal_tolerance: false 74 | 75 | # # Forward Simulation Parameters 76 | # sim_time: 2.0 77 | # sim_granularity: 0.02 78 | # vx_samples: 6 79 | # vy_samples: 0 80 | # vtheta_samples: 20 81 | # penalize_negative_x: true 82 | 83 | # # Trajectory scoring parameters 84 | # path_distance_bias: 32.0 # The weighting for how much the controller should stay close to the path it was given 85 | # goal_distance_bias: 24.0 # The weighting for how much the controller should attempt to reach its local goal, also controls speed 86 | # occdist_scale: 0.01 # The weighting for how much the controller should attempt to avoid obstacles 87 | # forward_point_distance: 0.325 # The distance from the center point of the robot to place an additional scoring point, in meters 88 | # stop_time_buffer: 0.2 # The amount of time that the robot must stThe absolute value of the veolicty at which to start scaling the robot's footprint, in m/sop before a collision in order for a trajectory to be considered valid in seconds 89 | # scaling_speed: 0.25 # The absolute value of the veolicty at which to start scaling the robot's footprint, in m/s 90 | # max_scaling_factor: 0.2 # The maximum factor to scale the robot's footprint by 91 | 92 | # # Oscillation Prevention Parameters 93 | # oscillation_reset_dist: 0.25 #How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05) -------------------------------------------------------------------------------- /limo/limo_bringup/param/ydlidar.yaml: -------------------------------------------------------------------------------- 1 | ydlidar_ros2_driver_node: 2 | ros__parameters: 3 | port: /dev/ydlidar 4 | frame_id: laser_frame 5 | ignore_array: "" 6 | baudrate: 115200 7 | lidar_type: 1 8 | device_type: 0 9 | sample_rate: 3 10 | abnormal_check_count: 4 11 | resolution_fixed: true 12 | reversion: true 13 | inverted: true 14 | auto_reconnect: true 15 | isSingleChannel: true 16 | intensity: false 17 | support_motor_dtr: false 18 | angle_max: 180.0 19 | angle_min: -180.0 20 | range_max: 12.0 21 | range_min: 0.01 22 | frequency: 8.0 23 | invalid_range_is_inf: false 24 | -------------------------------------------------------------------------------- /limo/limo_bringup/readme.md: -------------------------------------------------------------------------------- 1 | 2 | 下面的脚本一条一条运行, 注意不能在后台运行 3 | 4 | # 导航 5 | 6 | ```shell 7 | rviz2 8 | ## 启动底盘 9 | ros2 launch limo_bringup limo_start.launch.py 10 | sleep 2 11 | ## 启动导航 12 | ros2 launch limo_bringup limo_navigation.launch.py 13 | sleep 2 14 | ## 启动定位 15 | ros2 launch limo_bringup limo_localization.launch.py 16 | ``` 17 | 18 | # 建图 19 | 20 | ```shell 21 | ros2 launch limo_bringup limo_start.launch.py 22 | ros2 launch build_map_2d revo_build_map_2d.launch.py 23 | #上面三条指令启动之后,用遥控器控制车子行走 24 | # 建完图保存, 放到 limo_bringup/maps 里, 再 colcon build 编译一下XXX 25 | ``` 26 | 27 | 28 | # 键盘控制 29 | 30 | ```shell 31 | ros2 run teleop_twist_keyboard teleop_twist_keyboard 32 | ros2 launch limo_bringup limo_start.launch.py 33 | ``` 34 | -------------------------------------------------------------------------------- /limo/limo_bringup/scripts/mpu6050_test/blinkatest.py: -------------------------------------------------------------------------------- 1 | import board 2 | import busio 3 | 4 | print("hello") 5 | 6 | i2c = busio.I2C(board.SCL, board.SDA) 7 | print("I2C 1 ok") 8 | 9 | print("done") 10 | -------------------------------------------------------------------------------- /limo/limo_bringup/scripts/mpu6050_test/simple_test.py: -------------------------------------------------------------------------------- 1 | import board 2 | import time 3 | import adafruit_mpu6050 4 | 5 | # https://github.com/adafruit/Adafruit_CircuitPython_MPU6050/blob/main/examples/mpu6050_simpletest.py 6 | # 这个脚本各种报错,无法使用 7 | 8 | i2c = board.I2C() 9 | mpu = adafruit_mpu6050.MPU6050(i2c) 10 | 11 | while True: 12 | # 线加速度 13 | print("Acceleration: X:%.2f, Y:%.2f, Z:%.2f m/s^2" % (mpu.acceleration)) 14 | # 角加速度 15 | print("Gyro X:%.2f, Y:%.2f, Z:%.2f rad/s" % (mpu.gyro)) 16 | # 温度 17 | print("Temperature: %.2f C" % mpu.temperature) 18 | print("") 19 | 20 | time.sleep(1) 21 | print("done") 22 | -------------------------------------------------------------------------------- /limo/limo_bringup/scripts/mpu6050_test/use_smbus.py: -------------------------------------------------------------------------------- 1 | import smbus 2 | import time 3 | 4 | PWR_MGMT_1 = 0x6B 5 | SMPLRT_DIV = 0x19 6 | CONFIG = 0x1A 7 | GYRO_CONFIG = 0x1B 8 | INT_ENABLE = 0x38 9 | ACCEL_XOUT_H = 0x3B 10 | ACCEL_YOUT_H = 0x3D 11 | ACCEL_ZOUT_H = 0x3F 12 | GYRO_XOUT_H = 0x43 13 | GYRO_YOUT_H = 0x45 14 | GYRO_ZOUT_H = 0x47 15 | 16 | 17 | def MPU_Init(): 18 | print("mpu init...") 19 | # write to sample rate register 20 | bus.write_byte_data(Device_Address, SMPLRT_DIV, 7) 21 | 22 | # Write to power management register 23 | bus.write_byte_data(Device_Address, PWR_MGMT_1, 1) 24 | 25 | # Write to Configuration register 26 | bus.write_byte_data(Device_Address, CONFIG, 0) 27 | 28 | # Write to Gyro configuration register 29 | bus.write_byte_data(Device_Address, GYRO_CONFIG, 24) 30 | 31 | # Write to interrupt enable register 32 | bus.write_byte_data(Device_Address, INT_ENABLE, 1) 33 | 34 | 35 | def read_raw_data(addr): 36 | high = bus.read_byte_data(Device_Address, addr) 37 | low = bus.read_byte_data(Device_Address, addr+1) 38 | 39 | value = ((high << 8) | low) 40 | if(value > 32768): 41 | value = value - 65535 42 | return value 43 | 44 | 45 | bus = smbus.SMBus(1) 46 | Device_Address = 0x68 47 | MPU_Init() 48 | 49 | while True: 50 | #Read Accelerometer raw value 51 | acc_x = read_raw_data(ACCEL_XOUT_H) 52 | acc_y = read_raw_data(ACCEL_YOUT_H) 53 | acc_z = read_raw_data(ACCEL_ZOUT_H) 54 | 55 | #Read Gyroscope raw value 56 | gyro_x = read_raw_data(GYRO_XOUT_H) 57 | gyro_y = read_raw_data(GYRO_YOUT_H) 58 | gyro_z = read_raw_data(GYRO_ZOUT_H) 59 | 60 | #Full scale range +/- 250 degree/C as per sensitivity scale factor 61 | Ax = acc_x/16384.0 62 | Ay = acc_y/16384.0 63 | Az = acc_z/16384.0 64 | 65 | Gx = gyro_x/131.0 66 | Gy = gyro_y/131.0 67 | Gz = gyro_z/131.0 68 | 69 | 70 | print ("Gx=%.2f" %Gx, u'\u00b0'+ "/s", "\tGy=%.2f" %Gy, u'\u00b0'+ "/s", "\tGz=%.2f" %Gz, u'\u00b0'+ "/s", "\tAx=%.2f g" %Ax, "\tAy=%.2f g" %Ay, "\tAz=%.2f g" %Az) 71 | time.sleep(1) 72 | -------------------------------------------------------------------------------- /limo/limo_bringup/scripts/start_build_map_2d_ros2.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | roslaunch build_map_2d revo_build_map_2d.launch & 4 | sleep 3 5 | roslaunch limon_bringup limon_start.launch & 6 | sleep 2 -------------------------------------------------------------------------------- /limo/limo_bringup/setup.py: -------------------------------------------------------------------------------- 1 | import os 2 | from glob import glob 3 | from setuptools import setup 4 | 5 | package_name = 'limo_bringup' 6 | 7 | setup( 8 | data_files=[ 9 | (os.path.join('share', package_name), glob('launch/*.launch.py')) 10 | ] 11 | ) -------------------------------------------------------------------------------- /limo/limo_description/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(limo_description) 3 | 4 | # Default to C99 5 | if(NOT CMAKE_C_STANDARD) 6 | set(CMAKE_C_STANDARD 99) 7 | endif() 8 | 9 | # Default to C++14 10 | if(NOT CMAKE_CXX_STANDARD) 11 | set(CMAKE_CXX_STANDARD 14) 12 | endif() 13 | 14 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 15 | add_compile_options(-Wall -Wextra -Wpedantic) 16 | endif() 17 | 18 | # find dependencies 19 | find_package(ament_cmake REQUIRED) 20 | # uncomment the following section in order to fill in 21 | # further dependencies manually. 22 | # find_package( REQUIRED) 23 | install( 24 | DIRECTORY launch meshes rviz urdf 25 | DESTINATION share/${PROJECT_NAME} 26 | ) 27 | if(BUILD_TESTING) 28 | find_package(ament_lint_auto REQUIRED) 29 | # the following line skips the linter which checks for copyrights 30 | # uncomment the line when a copyright and license is not present in all source files 31 | #set(ament_cmake_copyright_FOUND TRUE) 32 | # the following line skips cpplint (only works in a git repo) 33 | # uncomment the line when this package is not in a git repo 34 | #set(ament_cmake_cpplint_FOUND TRUE) 35 | ament_lint_auto_find_test_dependencies() 36 | endif() 37 | 38 | ament_package() 39 | -------------------------------------------------------------------------------- /limo/limo_description/img/limo.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_description/img/limo.jpg -------------------------------------------------------------------------------- /limo/limo_description/launch/display_limo_ackerman.launch.py: -------------------------------------------------------------------------------- 1 | from ament_index_python.packages import get_package_share_path 2 | 3 | from launch import LaunchDescription 4 | from launch.actions import DeclareLaunchArgument 5 | from launch.conditions import IfCondition, UnlessCondition 6 | from launch.substitutions import Command, LaunchConfiguration 7 | 8 | from launch_ros.actions import Node 9 | from launch_ros.parameter_descriptions import ParameterValue 10 | 11 | def generate_launch_description(): 12 | urdf_tutorial_path = get_package_share_path('limo_description') 13 | default_model_path = urdf_tutorial_path / 'urdf/limo_ackerman.xacro' 14 | default_rviz_config_path = urdf_tutorial_path / 'rviz/rviz.rviz' 15 | 16 | gui_arg = DeclareLaunchArgument(name='gui', default_value='true', choices=['true', 'false'], 17 | description='Flag to enable joint_state_publisher_gui') 18 | model_arg = DeclareLaunchArgument(name='model', default_value=str(default_model_path), 19 | description='Absolute path to robot urdf file') 20 | rviz_arg = DeclareLaunchArgument(name='rvizconfig', default_value=str(default_rviz_config_path), 21 | description='Absolute path to rviz config file') 22 | 23 | robot_description = ParameterValue(Command(['xacro ', LaunchConfiguration('model')]), 24 | value_type=str) 25 | 26 | robot_state_publisher_node = Node( 27 | package='robot_state_publisher', 28 | executable='robot_state_publisher', 29 | parameters=[{'robot_description': robot_description}] 30 | ) 31 | 32 | # Depending on gui parameter, either launch joint_state_publisher or joint_state_publisher_gui 33 | joint_state_publisher_node = Node( 34 | package='joint_state_publisher', 35 | executable='joint_state_publisher', 36 | condition=UnlessCondition(LaunchConfiguration('gui')) 37 | ) 38 | 39 | joint_state_publisher_gui_node = Node( 40 | package='joint_state_publisher_gui', 41 | executable='joint_state_publisher_gui', 42 | condition=IfCondition(LaunchConfiguration('gui')) 43 | ) 44 | 45 | rviz_node = Node( 46 | package='rviz2', 47 | executable='rviz2', 48 | name='rviz2', 49 | output='screen', 50 | arguments=['-d', LaunchConfiguration('rvizconfig')], 51 | ) 52 | 53 | return LaunchDescription([ 54 | gui_arg, 55 | model_arg, 56 | rviz_arg, 57 | joint_state_publisher_node, 58 | joint_state_publisher_gui_node, 59 | robot_state_publisher_node, 60 | rviz_node 61 | ]) -------------------------------------------------------------------------------- /limo/limo_description/launch/display_limo_diff.launch.py: -------------------------------------------------------------------------------- 1 | from ament_index_python.packages import get_package_share_path 2 | 3 | from launch import LaunchDescription 4 | from launch.actions import DeclareLaunchArgument 5 | from launch.conditions import IfCondition, UnlessCondition 6 | from launch.substitutions import Command, LaunchConfiguration 7 | 8 | from launch_ros.actions import Node 9 | from launch_ros.parameter_descriptions import ParameterValue 10 | 11 | def generate_launch_description(): 12 | urdf_tutorial_path = get_package_share_path('limo_description') 13 | default_model_path = urdf_tutorial_path / 'urdf/limo_four_diff.xacro' 14 | default_rviz_config_path = urdf_tutorial_path / 'rviz/rviz.rviz' 15 | 16 | gui_arg = DeclareLaunchArgument(name='gui', default_value='true', choices=['true', 'false'], 17 | description='Flag to enable joint_state_publisher_gui') 18 | model_arg = DeclareLaunchArgument(name='model', default_value=str(default_model_path), 19 | description='Absolute path to robot urdf file') 20 | rviz_arg = DeclareLaunchArgument(name='rvizconfig', default_value=str(default_rviz_config_path), 21 | description='Absolute path to rviz config file') 22 | 23 | robot_description = ParameterValue(Command(['xacro ', LaunchConfiguration('model')]), 24 | value_type=str) 25 | 26 | robot_state_publisher_node = Node( 27 | package='robot_state_publisher', 28 | executable='robot_state_publisher', 29 | parameters=[{'robot_description': robot_description}] 30 | ) 31 | 32 | # Depending on gui parameter, either launch joint_state_publisher or joint_state_publisher_gui 33 | joint_state_publisher_node = Node( 34 | package='joint_state_publisher', 35 | executable='joint_state_publisher', 36 | condition=UnlessCondition(LaunchConfiguration('gui')) 37 | ) 38 | 39 | joint_state_publisher_gui_node = Node( 40 | package='joint_state_publisher_gui', 41 | executable='joint_state_publisher_gui', 42 | condition=IfCondition(LaunchConfiguration('gui')) 43 | ) 44 | 45 | rviz_node = Node( 46 | package='rviz2', 47 | executable='rviz2', 48 | name='rviz2', 49 | output='screen', 50 | arguments=['-d', LaunchConfiguration('rvizconfig')], 51 | ) 52 | 53 | return LaunchDescription([ 54 | gui_arg, 55 | model_arg, 56 | rviz_arg, 57 | joint_state_publisher_node, 58 | joint_state_publisher_gui_node, 59 | robot_state_publisher_node, 60 | rviz_node 61 | ]) -------------------------------------------------------------------------------- /limo/limo_description/meshes/limo_base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_description/meshes/limo_base.stl -------------------------------------------------------------------------------- /limo/limo_description/meshes/limo_wheel.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_description/meshes/limo_wheel.stl -------------------------------------------------------------------------------- /limo/limo_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | limo_description 5 | 0.0.0 6 | TODO: Package description 7 | q 8 | TODO: License declaration 9 | 10 | ament_cmake 11 | ament_cmake 12 | joint_state_publisher 13 | joint_state_publisher_gui 14 | 15 | 16 | rviz2 17 | xacro 18 | 19 | ament_lint_auto 20 | ament_lint_common 21 | 22 | 23 | ament_cmake 24 | 25 | 26 | -------------------------------------------------------------------------------- /limo/limo_description/urdf/limo_ackerman.gazebo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | Gazebo/Black 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | Gazebo/Black 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | Gazebo/Black 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | Gazebo/Black 51 | 52 | 53 | 54 | 55 | 56 | 57 | cmd_vel:=cmd_vel 58 | odom:=odom 59 | distance:=distance 60 | 61 | 100.0 62 | 63 | front_left_wheel 64 | front_right_wheel 65 | rear_left_wheel 66 | rear_right_wheel 67 | left_steering_hinge_wheel 68 | right_steering_hinge_wheel 69 | front_steer_joint 70 | 71 | 0.52 72 | 73 | 0.52 74 | 75 | 20 76 | 77 | 1500 0 1 78 | 0 0 79 | 1500 0 1 80 | 0 0 81 | 1000 0 1 82 | 0 0 83 | 84 | true 85 | true 86 | false 87 | true 88 | 89 | odom 90 | base_footprint 91 | 92 | 93 | 94 | 95 | 96 | -------------------------------------------------------------------------------- /limo/limo_description/urdf/limo_four_diff.gazebo: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 10 18 | 10 19 | 10000000.0 20 | 1.0 21 | 0.01 22 | 1 0 0 23 | 24 | 25 | 26 | 10 27 | 10 28 | 10000000.0 29 | 1.0 30 | 0.01 31 | 1 0 0 32 | 33 | 34 | 35 | 10 36 | 10 37 | 10000000.0 38 | 1.0 39 | 0.01 40 | 1 0 0 41 | 42 | 43 | 44 | 10 45 | 10 46 | 10000000.0 47 | 1.0 48 | 0.01 49 | 1 0 0 50 | 51 | 52 | 53 | 54 | 55 | 56 | / 57 | cmd_vel:=cmd_vel 58 | odom:=odom 59 | 60 | 61 | 30 62 | 2 63 | 64 | front_left_wheel 65 | front_right_wheel 66 | rear_left_wheel 67 | rear_right_wheel 68 | 69 | 0.172 70 | 0.172 71 | 72 | 0.09 73 | 0.09 74 | 75 | 76 | 1000 77 | 1.0 78 | true 79 | true 80 | true 81 | odom 82 | base_footprint 83 | 84 | 85 | 86 | 87 | -------------------------------------------------------------------------------- /limo/limo_description/urdf/limo_four_diff.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | -------------------------------------------------------------------------------- /limo/limo_gazebo_sim/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(limo_gazebo_sim) 3 | 4 | # Default to C99 5 | if(NOT CMAKE_C_STANDARD) 6 | set(CMAKE_C_STANDARD 99) 7 | endif() 8 | 9 | # Default to C++14 10 | if(NOT CMAKE_CXX_STANDARD) 11 | set(CMAKE_CXX_STANDARD 14) 12 | endif() 13 | 14 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 15 | add_compile_options(-Wall -Wextra -Wpedantic) 16 | endif() 17 | 18 | # find dependencies 19 | find_package(ament_cmake REQUIRED) 20 | # uncomment the following section in order to fill in 21 | # further dependencies manually. 22 | # find_package( REQUIRED) 23 | install( 24 | DIRECTORY launch rviz worlds 25 | DESTINATION share/${PROJECT_NAME} 26 | ) 27 | if(BUILD_TESTING) 28 | find_package(ament_lint_auto REQUIRED) 29 | # the following line skips the linter which checks for copyrights 30 | # uncomment the line when a copyright and license is not present in all source files 31 | #set(ament_cmake_copyright_FOUND TRUE) 32 | # the following line skips cpplint (only works in a git repo) 33 | # uncomment the line when this package is not in a git repo 34 | #set(ament_cmake_cpplint_FOUND TRUE) 35 | ament_lint_auto_find_test_dependencies() 36 | endif() 37 | 38 | ament_package() 39 | -------------------------------------------------------------------------------- /limo/limo_gazebo_sim/config/limo_ackerman_control.yaml: -------------------------------------------------------------------------------- 1 | # Publish all joint states ----------------------------------- 2 | limo_state_controller: 3 | type: joint_state_controller/JointStateController 4 | publish_rate: 100 5 | 6 | # Joint velocity controllers --------------------------------- 7 | /gazebo_ros_control/pid_gains: 8 | front_left_wheel: {p: 1.0, i: 0, d: 0.01} 9 | front_right_wheel: {p: 1.0, i: 0, d: 0.01} 10 | rear_left_wheel: {p: 1.0, i: 0, d: 0.01} 11 | rear_right_wheel: {p: 1.0, i: 0, d: 0.01} 12 | 13 | # Position Controllers --------------------------------------- 14 | limo_fl_steering_hinge_controller: 15 | type: effort_controllers/JointPositionController 16 | joint: left_steering_hinge_wheel 17 | pid: 18 | p: 100.0 19 | i: 0.1 20 | d: 0.1 21 | limo_fr_steering_hinge_controller: 22 | type: effort_controllers/JointPositionController 23 | joint: right_steering_hinge_wheel 24 | pid: 25 | p: 100.0 26 | i: 0.1 27 | d: 0.1 28 | -------------------------------------------------------------------------------- /limo/limo_gazebo_sim/config/limo_four_diff_control.yaml: -------------------------------------------------------------------------------- 1 | # Publish all joint states ----------------------------------- 2 | limo_state_controller: 3 | type: joint_state_controller/JointStateController 4 | publish_rate: 100 5 | /gazebo_ros_control/pid_gains: 6 | front_left_wheel: {p: 1.0, i: 0, d: 0.01} 7 | front_right_wheel: {p: 1.0, i: 0, d: 0.01} 8 | rear_left_wheel: {p: 1.0, i: 0, d: 0.01} 9 | rear_right_wheel: {p: 1.0, i: 0, d: 0.01} -------------------------------------------------------------------------------- /limo/limo_gazebo_sim/launch/limo_ackerman.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | 3 | from ament_index_python.packages import get_package_share_directory 4 | from launch import LaunchDescription 5 | from launch.actions import IncludeLaunchDescription 6 | from launch.launch_description_sources import PythonLaunchDescriptionSource 7 | 8 | 9 | def generate_launch_description(): 10 | #设置world的路径 11 | gazebo_world_path = os.path.join( 12 | get_package_share_directory('limo_gazebo_sim'), 'world', 'house.world') 13 | 14 | gazebo_options_dict = { 15 | 'world': gazebo_world_path, 16 | 'verbose': 'true' 17 | } 18 | 19 | gazebo_simulator = IncludeLaunchDescription( 20 | PythonLaunchDescriptionSource([ 21 | os.path.join(get_package_share_directory('gazebo_ros'), 'launch', 'gazebo.launch.py') 22 | ]), 23 | launch_arguments=gazebo_options_dict.items() 24 | ) 25 | 26 | car_sim_options = { 27 | 'start_x': '0', 28 | 'start_y': '0', 29 | 'start_z': '0', 30 | 'start_yaw': '0', 31 | 'pub_tf': 'true', 32 | 'tf_freq': '100.0', 33 | 'blue': 'false' 34 | } 35 | 36 | spawn_car = IncludeLaunchDescription( 37 | PythonLaunchDescriptionSource([ 38 | os.path.join( 39 | get_package_share_directory('limo_gazebo_sim'), 40 | 'launch', 'limo_ackerman_spawn.launch.py') 41 | ]), 42 | launch_arguments=car_sim_options.items() 43 | ) 44 | 45 | return LaunchDescription([ 46 | gazebo_simulator, 47 | spawn_car, 48 | ]) 49 | -------------------------------------------------------------------------------- /limo/limo_gazebo_sim/launch/limo_ackerman_spawn.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | 3 | from launch import LaunchDescription 4 | from launch.actions import DeclareLaunchArgument 5 | from launch.actions import SetEnvironmentVariable 6 | from launch.substitutions import Command, LaunchConfiguration 7 | from launch_ros.actions import Node 8 | from launch_ros.substitutions import FindPackageShare 9 | import launch_ros.descriptions 10 | import launch_ros 11 | import launch 12 | 13 | 14 | def generate_launch_description(): 15 | pkg_share = FindPackageShare(package='limo_description').find('limo_description') 16 | urdf_file = os.path.join(pkg_share, 'urdf/limo_ackerman.xacro') 17 | 18 | SetEnvironmentVariable('GAZEBO_MODEL_PATH', pkg_share) 19 | 20 | return LaunchDescription([ 21 | DeclareLaunchArgument('start_x', default_value='0.0', 22 | description='X coordinate of starting position'), 23 | DeclareLaunchArgument('start_y', default_value='0.0', 24 | description='Y coordinate of starting position'), 25 | DeclareLaunchArgument('start_z', default_value='0.0', 26 | description='Z coordinate of starting position'), 27 | DeclareLaunchArgument('start_yaw', default_value='0.0', 28 | description='Yaw angle of starting orientation'), 29 | DeclareLaunchArgument('robot_name', default_value='', 30 | description='Name and prefix for this robot'), 31 | Node( 32 | package='robot_state_publisher', 33 | executable='robot_state_publisher', 34 | name='robot_state_publisher', 35 | output='screen', 36 | # parameters=[{ 37 | # 'use_sim_time': True, 38 | # 'robot_description': Command( 39 | # [f'xacro {urdf_file}', ' robot_name:=', LaunchConfiguration('robot_name')]) 40 | parameters=[{'robot_description': launch_ros.descriptions.ParameterValue( launch.substitutions.Command([ 41 | 'xacro ',os.path.join(pkg_share,urdf_file)]), value_type=str) }] 42 | ), 43 | Node( 44 | package='gazebo_ros', 45 | executable='spawn_entity.py', 46 | arguments=[ 47 | '-entity', LaunchConfiguration('robot_name'), 48 | '-topic', 'robot_description', 49 | '-x', LaunchConfiguration('start_x'), 50 | '-y', LaunchConfiguration('start_y'), 51 | '-z', LaunchConfiguration('start_z'), 52 | '-Y', LaunchConfiguration('start_yaw'), 53 | '-timeout', '1000' 54 | ], 55 | output='screen') 56 | ]) 57 | -------------------------------------------------------------------------------- /limo/limo_gazebo_sim/launch/limo_diff.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | 3 | from ament_index_python.packages import get_package_share_directory 4 | from launch import LaunchDescription 5 | from launch.actions import IncludeLaunchDescription 6 | from launch.launch_description_sources import PythonLaunchDescriptionSource 7 | 8 | 9 | def generate_launch_description(): 10 | 11 | gazebo_world_path = os.path.join( 12 | get_package_share_directory('limo_gazebo_sim'), 'worlds', 'world_v1.world') 13 | 14 | gazebo_options_dict = { 15 | 'world': gazebo_world_path, 16 | 'verbose': 'true' 17 | } 18 | 19 | gazebo_simulator = IncludeLaunchDescription( 20 | PythonLaunchDescriptionSource([ 21 | os.path.join(get_package_share_directory('gazebo_ros'), 'launch', 'gazebo.launch.py') 22 | ]), 23 | launch_arguments=gazebo_options_dict.items() 24 | ) 25 | 26 | car_sim_options = { 27 | 'start_x': '0', 28 | 'start_y': '0', 29 | 'start_z': '0', 30 | 'start_yaw': '0', 31 | 'pub_tf': 'true', 32 | 'tf_freq': '100.0', 33 | 'blue': 'false' 34 | } 35 | 36 | spawn_car = IncludeLaunchDescription( 37 | PythonLaunchDescriptionSource([ 38 | os.path.join( 39 | get_package_share_directory('limo_gazebo_sim'), 40 | 'launch', 'limo_diff_spawn.launch.py') 41 | ]), 42 | launch_arguments=car_sim_options.items() 43 | ) 44 | 45 | return LaunchDescription([ 46 | gazebo_simulator, 47 | spawn_car, 48 | ]) 49 | -------------------------------------------------------------------------------- /limo/limo_gazebo_sim/launch/limo_diff_spawn.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | 3 | from launch import LaunchDescription 4 | from launch.actions import DeclareLaunchArgument 5 | from launch.actions import SetEnvironmentVariable 6 | from launch.substitutions import Command, LaunchConfiguration 7 | from launch_ros.actions import Node 8 | from launch_ros.substitutions import FindPackageShare 9 | import launch_ros.descriptions 10 | import launch_ros 11 | import launch 12 | 13 | 14 | def generate_launch_description(): 15 | pkg_share = FindPackageShare(package='limo_description').find('limo_description') 16 | urdf_file = os.path.join(pkg_share, 'urdf/limo_four_diff.xacro') 17 | 18 | SetEnvironmentVariable('GAZEBO_MODEL_PATH', pkg_share) 19 | 20 | return LaunchDescription([ 21 | DeclareLaunchArgument('start_x', default_value='0.0', 22 | description='X coordinate of starting position'), 23 | DeclareLaunchArgument('start_y', default_value='0.0', 24 | description='Y coordinate of starting position'), 25 | DeclareLaunchArgument('start_z', default_value='0.0', 26 | description='Z coordinate of starting position'), 27 | DeclareLaunchArgument('start_yaw', default_value='0.0', 28 | description='Yaw angle of starting orientation'), 29 | DeclareLaunchArgument('robot_name', default_value='', 30 | description='Name and prefix for this robot'), 31 | Node( 32 | package='robot_state_publisher', 33 | executable='robot_state_publisher', 34 | name='robot_state_publisher', 35 | output='screen', 36 | # parameters=[{ 37 | # 'use_sim_time': True, 38 | # 'robot_description': Command( 39 | # [f'xacro {urdf_file}', ' robot_name:=', LaunchConfiguration('robot_name')]) 40 | parameters=[{ 41 | 'use_sim_time': True, 42 | 'robot_description': launch_ros.descriptions.ParameterValue( launch.substitutions.Command([ 43 | 'xacro ',os.path.join(pkg_share,urdf_file)]), value_type=str) }] 44 | ), 45 | Node( 46 | package='gazebo_ros', 47 | executable='spawn_entity.py', 48 | arguments=[ 49 | '-entity', LaunchConfiguration('robot_name'), 50 | '-topic', 'robot_description', 51 | '-x', LaunchConfiguration('start_x'), 52 | '-y', LaunchConfiguration('start_y'), 53 | '-z', LaunchConfiguration('start_z'), 54 | '-Y', LaunchConfiguration('start_yaw'), 55 | '-timeout', '1000' 56 | ], 57 | output='screen') 58 | ]) 59 | -------------------------------------------------------------------------------- /limo/limo_gazebo_sim/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | limo_gazebo_sim 5 | 0.0.0 6 | TODO: Package limo_gazebo_sim 7 | q 8 | TODO: License declaration 9 | 10 | ament_cmake 11 | ament_cmake 12 | joint_state_publisher 13 | joint_state_publisher_gui 14 | 15 | 16 | rviz2 17 | xacro 18 | 19 | ament_lint_auto 20 | ament_lint_common 21 | 22 | 23 | ament_cmake 24 | 25 | 26 | -------------------------------------------------------------------------------- /limo/limo_gazebo_sim/worlds/empty.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | model://sun 7 | 8 | 9 | 10 | model://ground_plane 11 | 12 | 13 | 14 | 0.01 15 | 1 16 | 100 17 | 0 0 -9.8 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /limo/limo_gazebo_sim/worlds/willowgarage.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | model://ground_plane 6 | 7 | 8 | model://sun 9 | 10 | 11 | model://willowgarage 12 | 13 | 14 | 15 | 0.01 16 | 1 17 | 100 18 | 0 0 -9.8 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /limo/limo_gazebo_sim/worlds/world_v1/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | world_v1 4 | 1.0 5 | model.sdf 6 | 7 | 8 | 9 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /limo/limo_learnning/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | limo_learnning 5 | 0.0.0 6 | TODO: Package description 7 | agilex 8 | TODO: License declaration 9 | 10 | ament_cmake 11 | 12 | rclcpp 13 | std_msgs 14 | limo_msgs 15 | 16 | ament_lint_auto 17 | ament_lint_common 18 | rosidl_default_generators 19 | 20 | rosidl_default_runtime 21 | 22 | rosidl_interface_packages 23 | 24 | ament_cmake 25 | 26 | 27 | -------------------------------------------------------------------------------- /limo/limo_learnning/src/action.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | #include 4 | 5 | #include "example_interfaces/action/fibonacci.hpp" 6 | #include "rclcpp/rclcpp.hpp" 7 | 8 | #include "rclcpp_action/rclcpp_action.hpp" 9 | 10 | using Fibonacci = example_interfaces::action::Fibonacci; 11 | using GoalHandleFibonacci = rclcpp_action::ServerGoalHandle; 12 | 13 | rclcpp_action::GoalResponse handle_goal( 14 | const rclcpp_action::GoalUUID & uuid, std::shared_ptr goal) 15 | { 16 | RCLCPP_INFO(rclcpp::get_logger("server"), "Got goal request with order %d", goal->order); 17 | (void)uuid; 18 | // Let's reject sequences that are over 9000 19 | if (goal->order > 9000) { 20 | return rclcpp_action::GoalResponse::REJECT; 21 | } 22 | return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; 23 | } 24 | 25 | rclcpp_action::CancelResponse handle_cancel( 26 | const std::shared_ptr goal_handle) 27 | { 28 | RCLCPP_INFO(rclcpp::get_logger("server"), "Got request to cancel goal"); 29 | (void)goal_handle; 30 | return rclcpp_action::CancelResponse::ACCEPT; 31 | } 32 | 33 | void execute( 34 | const std::shared_ptr goal_handle) 35 | { 36 | RCLCPP_INFO(rclcpp::get_logger("server"), "Executing goal"); 37 | rclcpp::Rate loop_rate(1); 38 | const auto goal = goal_handle->get_goal(); 39 | auto feedback = std::make_shared(); 40 | auto & sequence = feedback->sequence; 41 | sequence.push_back(0); 42 | sequence.push_back(1); 43 | auto result = std::make_shared(); 44 | 45 | for (int i = 1; (i < goal->order) && rclcpp::ok(); ++i) { 46 | // Check if there is a cancel request 47 | if (goal_handle->is_canceling()) { 48 | result->sequence = sequence; 49 | goal_handle->canceled(result); 50 | RCLCPP_INFO(rclcpp::get_logger("server"), "Goal Canceled"); 51 | return; 52 | } 53 | // Update sequence 54 | sequence.push_back(sequence[i] + sequence[i - 1]); 55 | // Publish feedback 56 | goal_handle->publish_feedback(feedback); 57 | RCLCPP_INFO(rclcpp::get_logger("server"), "Publish Feedback"); 58 | 59 | loop_rate.sleep(); 60 | } 61 | 62 | // Check if goal is done 63 | if (rclcpp::ok()) { 64 | result->sequence = sequence; 65 | goal_handle->succeed(result); 66 | RCLCPP_INFO(rclcpp::get_logger("server"), "Goal Succeeded"); 67 | } 68 | } 69 | 70 | void handle_accepted(const std::shared_ptr goal_handle) 71 | { 72 | // this needs to return quickly to avoid blocking the executor, so spin up a new thread 73 | std::thread{execute, goal_handle}.detach(); 74 | } 75 | 76 | int main(int argc, char ** argv) 77 | { 78 | rclcpp::init(argc, argv); 79 | auto node = rclcpp::Node::make_shared("minimal_action_server"); 80 | 81 | // Create an action server with three callbacks 82 | // 'handle_goal' and 'handle_cancel' are called by the Executor (rclcpp::spin) 83 | // 'execute' is called whenever 'handle_goal' returns by accepting a goal 84 | // Calls to 'execute' are made in an available thread from a pool of four. 85 | auto action_server = rclcpp_action::create_server( 86 | node, 87 | "fibonacci", 88 | handle_goal, 89 | handle_cancel, 90 | handle_accepted); 91 | 92 | rclcpp::spin(node); 93 | 94 | rclcpp::shutdown(); 95 | return 0; 96 | } -------------------------------------------------------------------------------- /limo/limo_learnning/src/follow_path.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include "rclcpp/rclcpp.hpp" 6 | #include "geometry_msgs/msg/pose_stamped.hpp" 7 | #include "geometry_msgs/msg/twist.hpp" 8 | #include "tf2_ros/transform_listener.h" 9 | #include "tf2_ros/buffer.h" 10 | #include "tf2_geometry_msgs/tf2_geometry_msgs.h" 11 | 12 | class PathFollower : public rclcpp::Node { 13 | public: 14 | PathFollower() : Node("path_follower"), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { 15 | // 发布速度指令的Publisher 16 | cmd_vel_pub_ = this->create_publisher("/cmd_vel", 10); 17 | 18 | // 加载路径点 19 | loadPathPoints("recorded_path.txt"); 20 | 21 | // 定时器用于周期性调用路径跟踪函数 22 | timer_ = this->create_wall_timer( 23 | std::chrono::milliseconds(100), std::bind(&PathFollower::followPath, this)); 24 | } 25 | 26 | private: 27 | void loadPathPoints(const std::string &file_path) { 28 | std::ifstream path_file(file_path); 29 | if (!path_file.is_open()) { 30 | RCLCPP_ERROR(this->get_logger(), "无法打开路径点文件: %s", file_path.c_str()); 31 | return; 32 | } 33 | 34 | geometry_msgs::msg::PoseStamped pose; 35 | while (path_file >> pose.pose.position.x >> pose.pose.position.y >> pose.pose.position.z 36 | >> pose.pose.orientation.x >> pose.pose.orientation.y >> pose.pose.orientation.z >> pose.pose.orientation.w) { 37 | path_points_.push_back(pose); 38 | } 39 | 40 | path_file.close(); 41 | RCLCPP_INFO(this->get_logger(), "成功加载 %zu 个路径点。", path_points_.size()); 42 | } 43 | 44 | void followPath() { 45 | if (path_points_.empty()) { 46 | RCLCPP_INFO(this->get_logger(), "没有更多的路径点。"); 47 | return; 48 | } 49 | 50 | // 获取机器人当前位置(使用 TF 变换) 51 | geometry_msgs::msg::TransformStamped transform; 52 | try { 53 | transform = tf_buffer_.lookupTransform("map", "base_link", tf2::TimePointZero); 54 | } catch (tf2::TransformException &ex) { 55 | RCLCPP_WARN(this->get_logger(), "无法获取TF变换: %s", ex.what()); 56 | return; 57 | } 58 | geometry_msgs::msg::Quaternion quat = transform.transform.rotation; 59 | 60 | // 当前机器人位置 61 | double robot_x = transform.transform.translation.x; 62 | double robot_y = transform.transform.translation.y; 63 | // 提取偏航角 64 | tf2::Quaternion q; 65 | tf2::fromMsg(quat,q); 66 | tf2::Matrix3x3 M(q); 67 | double r, p, y; 68 | M.getRPY(r,p,y); 69 | double robot_yaw = y; 70 | 71 | // 当前目标点 72 | auto target_pose = path_points_.front(); 73 | double target_x = target_pose.pose.position.x; 74 | double target_y = target_pose.pose.position.y; 75 | 76 | // 计算距离和方向 77 | double distance = std::hypot(target_x - robot_x, target_y - robot_y); 78 | double angle_to_goal = std::atan2(target_y - robot_y, target_x - robot_x); 79 | double angle_error = angle_to_goal - robot_yaw; 80 | 81 | // 设置速度命令 82 | geometry_msgs::msg::Twist cmd_vel; 83 | cmd_vel.linear.x = 0.5 * distance; // 简单比例控制器调整线速度 84 | cmd_vel.angular.z = 1.0 * angle_error; // 简单比例控制器调整角速度 85 | 86 | // 发布速度命令 87 | cmd_vel_pub_->publish(cmd_vel); 88 | 89 | // 如果接近目标点,移到下一个点 90 | if (distance < 0.1) { 91 | path_points_.erase(path_points_.begin()); 92 | RCLCPP_INFO(this->get_logger(), "到达一个路径点,切换到下一个目标点。"); 93 | } 94 | } 95 | 96 | rclcpp::Publisher::SharedPtr cmd_vel_pub_; 97 | tf2_ros::Buffer tf_buffer_; 98 | tf2_ros::TransformListener tf_listener_; 99 | rclcpp::TimerBase::SharedPtr timer_; 100 | std::vector path_points_; 101 | }; 102 | 103 | int main(int argc, char **argv) { 104 | rclcpp::init(argc, argv); 105 | auto node = std::make_shared(); 106 | rclcpp::spin(node); 107 | rclcpp::shutdown(); 108 | return 0; 109 | } 110 | -------------------------------------------------------------------------------- /limo/limo_learnning/src/limo_client.cpp: -------------------------------------------------------------------------------- 1 | //导入头文件 2 | #include "rclcpp/rclcpp.hpp" 3 | #include 4 | #include 5 | #include 6 | #include 7 | // 使用标准的chrono库中的时间字面量 8 | using namespace std::chrono_literals; 9 | 10 | int main(int argc, char **argv) 11 | { 12 | rclcpp::init(argc, argv); 13 | //创建limo_client节点 14 | std::shared_ptr node = rclcpp::Node::make_shared("limo_client"); 15 | //创建一个客户端 16 | rclcpp::Client::SharedPtr client = 17 | node->create_client("limo_srv"); 18 | 19 | //创建一个服务请求对象,并设置请求参数 20 | auto request = std::make_shared(); 21 | request->x = 0.5; 22 | request->y = 0; 23 | request->z = 0.0; 24 | //等待服务,每一秒检查一次 25 | while (!client->wait_for_service(1s)) { 26 | if (!rclcpp::ok()) { 27 | RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Interrupted while waiting for the service. Exiting."); 28 | return 0; 29 | } 30 | RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "service not available, waiting again..."); 31 | } 32 | //发送请求 33 | auto result = client->async_send_request(request); 34 | //等待请求结果 35 | if (rclcpp::spin_until_future_complete(node, result) == 36 | rclcpp::FutureReturnCode::SUCCESS) 37 | { 38 | RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "success.data: %d", result.get()->success); 39 | } else { 40 | RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service limo_srv"); 41 | } 42 | 43 | rclcpp::shutdown(); 44 | return 0; 45 | } -------------------------------------------------------------------------------- /limo/limo_learnning/src/limo_scan.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | // 导入 ROS2 C++ 库 3 | #include 4 | // 从 geometry_msgs 接口导入 Twist 模块 5 | #include 6 | // 从 sensor_msgs 接口导入 LaserScan 模块 7 | 8 | class LimoScan : public rclcpp::Node { 9 | public: 10 | LimoScan() : Node("LimoScan") { 11 | // 创建发布器对象,发布 Twist 类型的消息到 'cmd_vel' 话题 12 | publisher_ = this->create_publisher("cmd_vel", 10); 13 | // 创建订阅器对象,订阅 '/scan' 话题,接收 LaserScan 类型的消息 14 | subscriber_ = this->create_subscription( 15 | "/scan", 16 | 10, 17 | std::bind(&LimoScan::laser_callback, this, std::placeholders::_1) 18 | ); 19 | // 定义计时器周期为 0.5 秒 20 | timer_ = this->create_wall_timer( 21 | std::chrono::milliseconds(500), 22 | std::bind(&LimoScan::motion, this) 23 | ); 24 | // 初始化激光前向距离为 0 25 | laser_forward_ = 0.0; 26 | } 27 | 28 | private: 29 | void laser_callback(const sensor_msgs::msg::LaserScan::SharedPtr msg) { 30 | // 保存前方激光扫描在 0° 的信息 31 | laser_forward_ = msg->ranges[359]; 32 | } 33 | 34 | void motion() { 35 | // 打印接收到的数据 36 | RCLCPP_INFO(this->get_logger(), "I receive: %f", laser_forward_); 37 | // 创建一个 Twist 消息对象 38 | auto cmd = geometry_msgs::msg::Twist(); 39 | 40 | // 移动逻辑 41 | if (laser_forward_ > 5.0) { 42 | // 如果前方距离大于 5 米,设定前进速度和旋转速度 43 | cmd.linear.x = 0.5; 44 | cmd.angular.z = 0.5; 45 | } else if (laser_forward_ < 5.0 && laser_forward_ >= 0.5) { 46 | // 如果前方距离在 0.5 米到 5 米之间,只设定前进速度 47 | cmd.linear.x = 0.2; 48 | cmd.angular.z = 0.0; 49 | } else { 50 | // 如果前方距离小于 0.5 米,停止运动 51 | cmd.linear.x = 0.0; 52 | cmd.angular.z = 0.0; 53 | } 54 | // 将计算出的速度命令发布到 'cmd_vel' 话题 55 | publisher_->publish(cmd); 56 | } 57 | 58 | rclcpp::Publisher::SharedPtr publisher_; 59 | rclcpp::Subscription::SharedPtr subscriber_; 60 | rclcpp::TimerBase::SharedPtr timer_; 61 | float laser_forward_; 62 | }; 63 | 64 | int main(int argc, char** argv) { 65 | // 初始化 ROS 通信 66 | rclcpp::init(argc, argv); 67 | // 创建一个节点对象 68 | auto node = std::make_shared(); 69 | // 暂停程序执行,等待节点被杀掉的请求(如按下 ctrl+c) 70 | rclcpp::spin(node); 71 | // 关闭 ROS 通信 72 | rclcpp::shutdown(); 73 | return 0; 74 | } -------------------------------------------------------------------------------- /limo/limo_learnning/src/limo_scan_nav.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | 6 | class CancelNav : public rclcpp::Node { 7 | public: 8 | CancelNav() : Node("cancel_navigation_node") { 9 | // 创建一个动作客户端,连接到导航动作服务器 10 | action_client_ = rclcpp_action::create_client( 11 | this, "navigate_to_pose"); 12 | 13 | subscriber_ = this->create_subscription( 14 | "/scan", 15 | 10, 16 | std::bind(&CancelNav::laser_callback, this, std::placeholders::_1) 17 | ); 18 | } 19 | 20 | private: 21 | void laser_callback(const sensor_msgs::msg::LaserScan::SharedPtr msg) { 22 | // 保存前方激光扫描在 0° 的信息 23 | laser_forward_ = msg->ranges[359]; 24 | laser_data(laser_forward_); 25 | } 26 | 27 | void laser_data(const float &msg) { 28 | // 打印接收到的数据 29 | RCLCPP_INFO(this->get_logger(), "I receive: %f", msg); 30 | if (msg<1.0) 31 | { 32 | cancel_navigation(); 33 | } 34 | 35 | } 36 | void cancel_navigation() { 37 | if (!action_client_->wait_for_action_server(std::chrono::seconds(5))) { 38 | RCLCPP_ERROR(this->get_logger(), "导航Action服务未上线"); 39 | return; 40 | } 41 | 42 | auto future = action_client_->async_cancel_all_goals(); 43 | std::cout<<"cancel_result: "<return_code; 46 | std::cout<<"cancel_result: "<get_logger(), "取消导航目标成功"); 50 | } else { 51 | RCLCPP_ERROR(this->get_logger(), "取消导航目标失败"); 52 | } 53 | } 54 | 55 | rclcpp_action::Client::SharedPtr action_client_; 56 | rclcpp::Subscription::SharedPtr subscriber_; 57 | float laser_forward_; 58 | 59 | }; 60 | 61 | int main(int argc, char** argv) { 62 | rclcpp::init(argc, argv); 63 | 64 | auto node = std::make_shared(); 65 | 66 | rclcpp::spin(node); 67 | rclcpp::shutdown(); 68 | 69 | return 0; 70 | } 71 | -------------------------------------------------------------------------------- /limo/limo_learnning/src/limo_server.cpp: -------------------------------------------------------------------------------- 1 | // 导入头文件 2 | #include "rclcpp/rclcpp.hpp" 3 | #include 4 | #include 5 | #include 6 | #include 7 | // 导入智能指针库 8 | #include 9 | 10 | // 定义Twist消息对象,用于速度命令 11 | geometry_msgs::msg::Twist vel_cmd; 12 | // 定义一个发布者 13 | rclcpp::Publisher::SharedPtr pub_vel; 14 | 15 | int count = 0 ; 16 | 17 | // 定义服务回调函数 18 | void limo_srv( 19 | const std::shared_ptr request, // 请求 20 | std::shared_ptr response //响应 21 | ) 22 | { 23 | while (rclcpp::ok()) 24 | { 25 | 26 | if (count < 4) 27 | { 28 | // 将请求的数据 赋值给vel_cmd 29 | vel_cmd.linear.x = request->x; 30 | vel_cmd.linear.y = request->y; 31 | vel_cmd.angular.z = request->z; 32 | // 发布话题消息 33 | pub_vel->publish(vel_cmd); 34 | // 输出日志信息,提示已经完成话题发布 35 | RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Publishing: linear.x: %f, angular.z: %f", 36 | vel_cmd.linear.x, vel_cmd.angular.z); 37 | rclcpp::sleep_for(std::chrono::microseconds(500)); 38 | 39 | } 40 | else 41 | { 42 | vel_cmd.linear.x = 0.0; 43 | vel_cmd.linear.y = 0.0; 44 | vel_cmd.linear.z = 0.0; 45 | vel_cmd.angular.z = 0; 46 | // 发布话题消息 47 | pub_vel->publish(vel_cmd); 48 | // 输出日志信息,提示已经完成话题发布 49 | RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Publishing: linear.x: %f, angular.z: %f", 50 | vel_cmd.linear.x, vel_cmd.angular.z); 51 | response->success = true; 52 | break; 53 | } 54 | count++; 55 | 56 | // 打印请求和响应的日志信息 57 | RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"request->x: %lf",request->x); 58 | RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"request->y: %lf",request->y); 59 | RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"request->z: %lf",request->z); 60 | RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"response->success.data: %d",response->success); 61 | 62 | } 63 | } 64 | 65 | int main(int argc, char** argv) 66 | { 67 | 68 | rclcpp::init(argc, argv); 69 | 70 | std::shared_ptr node = rclcpp::Node::make_shared("limo_srv"); 71 | //创建服务 72 | rclcpp::Service::SharedPtr service= 73 | node->create_service("limo_srv", &limo_srv); 74 | 75 | pub_vel = node->create_publisher("cmd_vel",10); 76 | rclcpp::spin(node); 77 | rclcpp::shutdown(); 78 | return 0; 79 | } 80 | -------------------------------------------------------------------------------- /limo/limo_learnning/src/limo_topic_cmd.cpp: -------------------------------------------------------------------------------- 1 | 2 | //导入头文件 3 | #include "rclcpp/rclcpp.hpp" 4 | #include "std_msgs/msg/string.hpp" 5 | #include "geometry_msgs/msg/twist.hpp" 6 | #include "nav_msgs/msg/odometry.hpp" 7 | 8 | using namespace std::chrono_literals; 9 | 10 | //自定义一个LimoTopicCmd并继承rclcpp::Node 11 | class LimoTopicCmd : public rclcpp::Node 12 | { 13 | private: 14 | //定义一个周期性执行的回调函数 15 | void timer_callback() 16 | { 17 | geometry_msgs::msg::Twist vel_cmd; 18 | 19 | //检查计数器次数 20 | if (count < 4) 21 | { 22 | //填入速度信息 23 | vel_cmd.linear.x = 0.1; 24 | vel_cmd.linear.y = 0.0; 25 | vel_cmd.linear.z = 0.0; 26 | vel_cmd.angular.z = 0; 27 | // 发布话题消息 28 | pub_vel->publish(vel_cmd); 29 | // 输出日志信息,提示已经完成话题发布 30 | RCLCPP_INFO(this->get_logger(), "Publishing: linear.x: %f, angular.z: %f", 31 | vel_cmd.linear.x, vel_cmd.angular.z); 32 | 33 | } 34 | else 35 | { 36 | vel_cmd.linear.x = 0.0; 37 | vel_cmd.linear.y = 0.0; 38 | vel_cmd.linear.z = 0.0; 39 | vel_cmd.angular.z = 0; 40 | // 发布话题消息 41 | pub_vel->publish(vel_cmd); 42 | // 输出日志信息,提示已经完成话题发布 43 | RCLCPP_INFO(this->get_logger(), "Publishing: linear.x: %f, angular.z: %f", 44 | vel_cmd.linear.x, vel_cmd.angular.z); 45 | 46 | } 47 | count++; 48 | } 49 | // 定义速度命令消息对象 50 | geometry_msgs::msg::Twist vel_cmd; 51 | // 定义发布者 52 | rclcpp::Publisher::SharedPtr pub_vel; 53 | // 定义定时器指针 54 | rclcpp::TimerBase::SharedPtr timer_; 55 | // 定义计数器 56 | int count = 0; 57 | 58 | public: 59 | 60 | LimoTopicCmd() : Node ("LimoTopicCmd") 61 | { 62 | // 创建速度命令发布者,发布到 /cmd_vel 话题,队列大小为10 63 | pub_vel = this-> create_publisher("/cmd_vel",10); 64 | // 创建一个定时器,每500毫秒调用一次 timer_callback 函数 65 | timer_ = this->create_wall_timer( 66 | 500ms, std::bind(&LimoTopicCmd::timer_callback, this)); 67 | } 68 | 69 | }; 70 | 71 | 72 | 73 | int main(int argc, char * argv[]) 74 | { 75 | rclcpp::init(argc, argv); 76 | 77 | // 创建一个LimoTopicCmd节点对象并进入循环,等待和处理ROS2消息 78 | rclcpp::spin(std::make_shared()); 79 | 80 | // 关闭ROS2 C++接口 81 | rclcpp::shutdown(); 82 | 83 | return 0; 84 | } -------------------------------------------------------------------------------- /limo/limo_learnning/src/listen_tf.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | 7 | int main(int argc, char** argv) 8 | { 9 | rclcpp::init(argc, argv); 10 | auto node = rclcpp::Node::make_shared("tf_listener"); 11 | 12 | tf2_ros::Buffer tf_buffer(node->get_clock()); 13 | tf2_ros::TransformListener tf_listener(tf_buffer); 14 | 15 | rclcpp::Rate rate(10); // 10 Hz 16 | 17 | static tf2_ros::StaticTransformBroadcaster static_broadcaster(node); 18 | 19 | while (rclcpp::ok()) 20 | { 21 | try 22 | { 23 | // 获取base_link坐标变换 24 | geometry_msgs::msg::TransformStamped base_link_transform; 25 | base_link_transform = tf_buffer.lookupTransform("base_link", "imu_link", tf2::TimePointZero); 26 | 27 | RCLCPP_INFO(node->get_logger(), "Received TF: [%s] -> [%s]", 28 | base_link_transform.header.frame_id.c_str(), 29 | base_link_transform.child_frame_id.c_str()); 30 | 31 | // 虚拟一个跟随base_link的TF坐标,根据base_link的TF进行平移和旋转 32 | 33 | geometry_msgs::msg::TransformStamped virtual_transform; 34 | virtual_transform.header.stamp = node->get_clock()->now(); 35 | virtual_transform.header.frame_id = "base_link"; 36 | virtual_transform.child_frame_id = "virtual_frame"; 37 | virtual_transform.transform.translation.x = sqrt(pow(base_link_transform.transform.translation.x,2)) 38 | +sqrt(pow(base_link_transform.transform.translation.y,2)); 39 | virtual_transform.transform.translation.y = base_link_transform.transform.translation.y + 0.1; 40 | virtual_transform.transform.translation.z = base_link_transform.transform.translation.z; 41 | virtual_transform.transform.rotation = base_link_transform.transform.rotation; 42 | 43 | static_broadcaster.sendTransform(virtual_transform); 44 | } 45 | catch (tf2::TransformException &ex) 46 | { 47 | RCLCPP_WARN(node->get_logger(), "%s", ex.what()); 48 | } 49 | 50 | rate.sleep(); 51 | } 52 | 53 | rclcpp::shutdown(); 54 | return 0; 55 | } 56 | -------------------------------------------------------------------------------- /limo/limo_learnning/src/multi_goal_nav_back.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "nav2_msgs/action/navigate_to_pose.hpp" 4 | #include "rclcpp/rclcpp.hpp" 5 | #include "rclcpp_action/rclcpp_action.hpp" 6 | 7 | using NavigationAction = nav2_msgs::action::NavigateToPose; 8 | 9 | class NavToPoseClient : public rclcpp::Node { 10 | public: 11 | using NavigationActionClient = rclcpp_action::Client; 12 | using NavigationActionGoalHandle = 13 | rclcpp_action::ClientGoalHandle; 14 | 15 | NavToPoseClient() : Node("nav_to_pose_client") { 16 | action_client_ = rclcpp_action::create_client( 17 | this, "navigate_to_pose"); 18 | 19 | // 添加多个导航目标点到目标队列 20 | addGoals(); 21 | } 22 | 23 | void sendGoal() { 24 | // 如果目标队列为空,结束导航 25 | if (goals_.empty()) { 26 | RCLCPP_INFO(get_logger(), "所有目标点已完成导航。"); 27 | return; 28 | } 29 | 30 | // 等待导航动作服务器上线,等待时间为5秒 31 | while (!action_client_->wait_for_action_server(std::chrono::seconds(5))) { 32 | RCLCPP_INFO(get_logger(), "等待Action服务上线。"); 33 | } 34 | 35 | // 取出第一个目标点并从队列中移除 36 | auto goal_msg = goals_.front(); 37 | goals_.erase(goals_.begin()); 38 | 39 | auto send_goal_options = 40 | rclcpp_action::Client::SendGoalOptions(); 41 | 42 | send_goal_options.goal_response_callback = 43 | [this](NavigationActionGoalHandle::SharedPtr goal_handle) { 44 | if (goal_handle) { 45 | RCLCPP_INFO(get_logger(), "目标点已被服务器接收"); 46 | } 47 | }; 48 | 49 | send_goal_options.feedback_callback = 50 | [this]( 51 | NavigationActionGoalHandle::SharedPtr goal_handle, 52 | const std::shared_ptr feedback) { 53 | (void)goal_handle; 54 | RCLCPP_INFO(this->get_logger(), "反馈剩余距离:%f", 55 | feedback->distance_remaining); 56 | }; 57 | 58 | send_goal_options.result_callback = 59 | [this](const NavigationActionGoalHandle::WrappedResult& result) { 60 | if (result.code == rclcpp_action::ResultCode::SUCCEEDED) { 61 | RCLCPP_INFO(this->get_logger(), "目标点导航成功!"); 62 | // 发送下一个目标点 63 | this->sendGoal(); 64 | } else { 65 | RCLCPP_ERROR(this->get_logger(), "目标点导航失败。"); 66 | } 67 | }; 68 | 69 | // 发送导航目标点 70 | action_client_->async_send_goal(goal_msg, send_goal_options); 71 | } 72 | 73 | private: 74 | void addGoals() { 75 | // 创建并添加第一个目标点 76 | NavigationAction::Goal goal_1; 77 | goal_1.pose.header.frame_id = "map"; 78 | goal_1.pose.pose.position.x = 1.0f; 79 | goal_1.pose.pose.position.y = 1.0f; 80 | goals_.push_back(goal_1); 81 | 82 | // 创建并添加第二个目标点 83 | NavigationAction::Goal goal_2; 84 | goal_2.pose.header.frame_id = "map"; 85 | goal_2.pose.pose.position.x = 2.0f; 86 | goal_2.pose.pose.position.y = 1.0f; 87 | goals_.push_back(goal_2); 88 | 89 | // 继续添加更多目标点... 90 | } 91 | 92 | std::vector goals_; // 目标点队列 93 | NavigationActionClient::SharedPtr action_client_; 94 | }; 95 | 96 | int main(int argc, char** argv) { 97 | rclcpp::init(argc, argv); 98 | auto node = std::make_shared(); 99 | node->sendGoal(); 100 | rclcpp::spin(node); 101 | rclcpp::shutdown(); 102 | return 0; 103 | } 104 | -------------------------------------------------------------------------------- /limo/limo_learnning/src/record_path.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include "rclcpp/rclcpp.hpp" 7 | #include "geometry_msgs/msg/pose_stamped.hpp" 8 | #include "tf2_geometry_msgs/tf2_geometry_msgs.h" 9 | 10 | class PathRecorder : public rclcpp::Node { 11 | public: 12 | PathRecorder() : Node("path_recorder"), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { 13 | // 初始化计时器,每秒执行一次 14 | timer_ = this->create_wall_timer( 15 | std::chrono::seconds(1), std::bind(&PathRecorder::recordPathPoint, this)); 16 | 17 | // 打开文件以记录路径点 18 | path_file_.open("recorded_path.txt", std::ios::out); 19 | if (!path_file_.is_open()) { 20 | RCLCPP_ERROR(this->get_logger(), "无法打开文件以记录路径点。"); 21 | } 22 | } 23 | 24 | ~PathRecorder() { 25 | // 关闭文件 26 | if (path_file_.is_open()) { 27 | path_file_.close(); 28 | } 29 | } 30 | 31 | private: 32 | void recordPathPoint() { 33 | // 获取机器人当前位置(使用 TF 变换) 34 | geometry_msgs::msg::TransformStamped transform; 35 | try { 36 | transform = tf_buffer_.lookupTransform("map", "base_footprint", tf2::TimePointZero); 37 | } catch (tf2::TransformException &ex) { 38 | RCLCPP_WARN(this->get_logger(), "无法获取TF变换: %s", ex.what()); 39 | return; 40 | } 41 | 42 | // 创建一个 PoseStamped 消息 43 | geometry_msgs::msg::PoseStamped pose; 44 | pose.header.stamp = transform.header.stamp; 45 | pose.header.frame_id = "map"; 46 | pose.pose.position.x = transform.transform.translation.x; 47 | pose.pose.position.y = transform.transform.translation.y; 48 | pose.pose.position.z = transform.transform.translation.z; 49 | pose.pose.orientation = transform.transform.rotation; 50 | 51 | // 打印路径点信息 52 | RCLCPP_INFO(this->get_logger(), "记录路径点: x=%f, y=%f, z=%f", 53 | pose.pose.position.x, pose.pose.position.y, pose.pose.position.z); 54 | 55 | // 将路径点保存到文件 56 | if (path_file_.is_open()) { 57 | path_file_ << pose.pose.position.x << " " 58 | << pose.pose.position.y << " " 59 | << pose.pose.position.z << " " 60 | << pose.pose.orientation.x << " " 61 | << pose.pose.orientation.y << " " 62 | << pose.pose.orientation.z << " " 63 | << pose.pose.orientation.w << std::endl; 64 | } 65 | } 66 | 67 | tf2_ros::Buffer tf_buffer_; 68 | tf2_ros::TransformListener tf_listener_; 69 | rclcpp::TimerBase::SharedPtr timer_; 70 | std::ofstream path_file_; 71 | }; 72 | 73 | int main(int argc, char **argv) { 74 | rclcpp::init(argc, argv); 75 | auto node = std::make_shared(); 76 | rclcpp::spin(node); 77 | rclcpp::shutdown(); 78 | return 0; 79 | } 80 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/limo_learnning_py/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_learnning_py/limo_learnning_py/__init__.py -------------------------------------------------------------------------------- /limo/limo_learnning_py/limo_learnning_py/limo_action_client.py: -------------------------------------------------------------------------------- 1 | import rclpy # 导入ROS 2 Python客户端库 2 | from rclpy.node import Node # 导入节点类 3 | from rclpy.action import ActionClient # 导入动作客户端类 4 | # from rclpy.action import ClientGoalHandle # 导入客户端目标句柄类 5 | from limo_msgs.action import LimoAction # 导入自定义动作消息类型 6 | import sys # 导入系统模块 7 | 8 | class LimoActionClient(Node): # 定义LimoActionClient类,继承自Node 9 | 10 | def __init__(self): # 构造函数 11 | super().__init__('limo_action_client') # 初始化节点名称为'limo_action_client' 12 | self.action_client = ActionClient(self, LimoAction, 'limo_action') # 创建动作客户端 13 | 14 | def send_goal(self): # 定义发送目标的函数 15 | if not self.action_client.wait_for_server(timeout_sec=20.0): # 等待动作服务器20秒 16 | self.get_logger().error('Action server not available after waiting') # 如果服务器不可用,记录错误日志 17 | rclpy.shutdown() # 关闭节点 18 | return # 返回退出函数 19 | 20 | goal_msg = LimoAction.Goal() # 创建目标消息 21 | goal_msg.x = 1.0 # 设置目标x坐标 22 | goal_msg.y = 0.0 # 设置目标y坐标 23 | goal_msg.z = 0.5 # 设置目标z坐标 24 | 25 | self.get_logger().info('Sending goal') # 记录发送目标的日志 26 | 27 | self.action_client.wait_for_server() # 再次等待动作服务器 28 | # 异步发送目标,并绑定反馈回调函数 29 | # self.action_client.send_goal_async(goal_msg, feedback_callback= 30 | # self.feedback_callback).add_done_callback(self.goal_response_callback) 31 | 32 | self.send_goal_future = self.action_client.send_goal_async(goal_msg, 33 | feedback_callback=self.feedback_callback) 34 | self.send_goal_future.add_done_callback(self.goal_response_callback) 35 | 36 | def goal_response_callback(self, future): # 定义目标响应回调函数 37 | goal_handle = future.result() # 接受结果 38 | if not goal_handle.accepted: # 如果目标未被接受 39 | self.get_logger().error('Client: Goal was rejected by server') # 记录目标被拒绝的错误日志 40 | rclpy.shutdown() # 关闭节点 41 | return # 返回退出函数 42 | 43 | self.get_logger().info('Client: Goal accepted by server, waiting for result') # 记录目标被接受的日志 44 | # goal_handle.get_result_async().add_done_callback(self.result_callback) # 异步获取结果,并绑定结果回调函数 45 | self.get_result_future = goal_handle.get_result_async() 46 | self.get_result_future.add_done_callback(self.result_callback) 47 | 48 | def feedback_callback(self, feedback_message): # 定义反馈回调函数 49 | feedback = feedback_message.feedback 50 | self.get_logger().info(f'Client: Received feedback: {feedback.status}') # 记录收到的反馈信息 51 | 52 | def result_callback(self, future): # 定义结果回调函数 53 | result = future.result().result # 获取结果 54 | self.get_logger().info('Result: %d' % result.success) 55 | 56 | def main(args=None): # 定义主函数 57 | rclpy.init(args=args) # 初始化rclpy 58 | action_client = LimoActionClient() # 创建LimoActionClient对象 59 | action_client.send_goal() # 发送目标 60 | rclpy.spin(action_client) # 保持节点运行 61 | 62 | if __name__ == '__main__': # 如果是主程序入口 63 | main() # 调用主函数 64 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/limo_learnning_py/limo_action_server.py: -------------------------------------------------------------------------------- 1 | import rclpy # 导入ROS 2的Python客户端库 2 | from rclpy.node import Node # 导入Node类以创建ROS 2节点 3 | from rclpy.action import ActionServer, CancelResponse, GoalResponse # 导入ActionServer类和相关响应类 4 | from geometry_msgs.msg import Twist # 导入Twist消息类型,用于发布速度命令 5 | from limo_msgs.action import LimoAction # 导入LimoAction消息类型 6 | import threading # 导入线程库,用于并发处理 7 | import time # 导入时间库,用于延时处理 8 | 9 | # 定义LimoActionServer类,继承自Node 10 | class LimoActionServer(Node): 11 | 12 | def __init__(self): # 构造函数 13 | super().__init__('limo_action_server') # 初始化节点,命名为'limo_action_server' 14 | self.pub_vel = self.create_publisher(Twist, 'cmd_vel', 10) # 创建速度命令发布者,发布到'cmd_vel'话题 15 | self.limo_action_server = ActionServer( # 创建动作服务器 16 | self, # 当前节点 17 | LimoAction, # 动作类型 18 | 'limo_action', # 动作名称 19 | execute_callback=self.execute_callback, # 执行目标的回调函数 20 | ) 21 | 22 | def execute_callback(self, goal_handle): # 执行目标的回调函数 23 | self.get_logger().info('Executing goal') # 记录正在执行目标的信息 24 | vel_cmd = Twist() # 创建Twist消息实例 25 | feedback_msg = LimoAction.Feedback() # 创建反馈消息实例 26 | result = LimoAction.Result() # 创建结果消息实例 27 | 28 | vel_cmd.linear.x = goal_handle.request.x # 设置线速度X值 29 | vel_cmd.linear.y = goal_handle.request.y # 设置线速度Y值 30 | vel_cmd.angular.z = goal_handle.request.z # 设置角速度Z值 31 | 32 | if goal_handle.is_active: # 如果目标句柄处于活动状态 33 | self.pub_vel.publish(vel_cmd) # 发布速度命令 34 | self.get_logger().info('Goal Succeeded') # 记录目标成功的信息 35 | goal_handle.succeed() # 标记目标成功 36 | result.success = True # 设置结果成功 37 | 38 | feedback_msg.status = 1 # 设置反馈消息状态 39 | goal_handle.publish_feedback(feedback_msg) # 发布反馈消息 40 | 41 | time.sleep(2) # 延时2秒 42 | 43 | vel_cmd.linear.x = 0.0 # 停止线速度X 44 | vel_cmd.linear.y = 0.0 # 停止线速度Y 45 | vel_cmd.angular.z = 0.0 # 停止角速度Z 46 | self.pub_vel.publish(vel_cmd) # 发布停止命令 47 | result.success = True 48 | return result # 返回结果消息 49 | 50 | def main(args=None): # 主函数 51 | rclpy.init(args=args) # 初始化rclpy 52 | action_server = LimoActionServer() # 创建LimoActionServer实例 53 | rclpy.spin(action_server) # 保持节点运行,等待和处理ROS 2消息 54 | rclpy.shutdown() # 关闭rclpy 55 | 56 | if __name__ == '__main__': # 检查是否为主程序入口 57 | main() # 调用主函数 58 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/limo_learnning_py/limo_client.py: -------------------------------------------------------------------------------- 1 | import rclpy 2 | from rclpy.node import Node 3 | from limo_msgs.srv import LimoSrv 4 | from geometry_msgs.msg import Twist 5 | from std_msgs.msg import Bool 6 | import time 7 | 8 | class LimoClient(Node): 9 | 10 | def __init__(self): 11 | super().__init__('limo_client') 12 | self.client = self.create_client(LimoSrv, 'limo_srv') 13 | while not self.client.wait_for_service(timeout_sec=1.0): 14 | self.get_logger().info('Service not available, waiting again...') 15 | 16 | def send_request(self): 17 | request = LimoSrv.Request() 18 | request.x = 0.5 19 | request.y = 0.0 20 | request.z = 0.0 21 | 22 | future = self.client.call_async(request) 23 | rclpy.spin_until_future_complete(self, future) 24 | return future.result() 25 | 26 | 27 | def main(args=None): 28 | rclpy.init(args=args) 29 | node = LimoClient() 30 | response = node.send_request() 31 | 32 | if response is not None: 33 | node.get_logger().info(f'success.data: {response.success}') 34 | else: 35 | node.get_logger().error('Failed to call service limo_srv') 36 | 37 | rclpy.shutdown() 38 | 39 | if __name__ == '__main__': 40 | main() 41 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/limo_learnning_py/limo_scan.py: -------------------------------------------------------------------------------- 1 | import rclpy 2 | # 导入 ROS2 Python 库 3 | from rclpy.node import Node 4 | # 从 geometry_msgs 接口导入 Twist 模块 5 | from geometry_msgs.msg import Twist 6 | # 从 sensor_msgs 接口导入 LaserScan 模块 7 | from sensor_msgs.msg import LaserScan 8 | from rclpy.qos import ReliabilityPolicy, QoSProfile 9 | 10 | # 定义一个类继承自 Node 11 | class Exercise31(Node): 12 | 13 | def __init__(self): 14 | # 调用父类构造函数,初始化节点 15 | super().__init__('exercise31') 16 | # 创建一个发布器对象,发布 Twist 类型的消息到 'cmd_vel' 话题 17 | self.publisher_ = self.create_publisher(Twist, 'cmd_vel', 10) 18 | # 创建一个订阅器对象,订阅 '/scan' 话题,接收 LaserScan 类型的消息 19 | self.subscriber = self.create_subscription( 20 | LaserScan, 21 | '/scan', 22 | self.laser_callback, 23 | QoSProfile(depth=10, reliability=ReliabilityPolicy.RELIABLE) 24 | ) 25 | # 定义计时器周期为 0.5 秒 26 | self.timer_period = 0.5 27 | # 定义变量以保存接收到的激光数据 28 | self.laser_forward = 0 29 | # 创建一个 Twist 消息对象 30 | self.cmd = Twist() 31 | # 创建一个定时器,每 0.5 秒调用一次 self.motion 方法 32 | self.timer = self.create_timer(self.timer_period, self.motion) 33 | 34 | def laser_callback(self, msg): 35 | # 保存前方激光扫描在 0° 的信息 36 | self.laser_forward = msg.ranges[359] 37 | 38 | def motion(self): 39 | # 打印接收到的数据 40 | self.get_logger().info('I receive: "%s"' % str(self.laser_forward)) 41 | # 移动逻辑 42 | if self.laser_forward > 5: 43 | # 如果前方距离大于 5 米,设定前进速度和旋转速度 44 | self.cmd.linear.x = 0.5 45 | self.cmd.angular.z = 0.5 46 | elif self.laser_forward < 5 and self.laser_forward >= 0.5: 47 | # 如果前方距离在 0.5 米到 5 米之间,只设定前进速度 48 | self.cmd.linear.x = 0.2 49 | self.cmd.angular.z = 0.0 50 | else: 51 | # 如果前方距离小于 0.5 米,停止运动 52 | self.cmd.linear.x = 0.0 53 | self.cmd.angular.z = 0.0 54 | 55 | # 将计算出的速度命令发布到 'cmd_vel' 话题 56 | self.publisher_.publish(self.cmd) 57 | 58 | def main(args=None): 59 | # 初始化 ROS 通信 60 | rclpy.init(args=args) 61 | # 声明节点构造函数 62 | exercise31 = Exercise31() 63 | # 暂停程序执行,等待节点被杀掉的请求(如按下 ctrl+c) 64 | rclpy.spin(exercise31) 65 | # 显式销毁节点 66 | exercise31.destroy_node() 67 | # 关闭 ROS 通信 68 | rclpy.shutdown() 69 | 70 | if __name__ == '__main__': 71 | main() -------------------------------------------------------------------------------- /limo/limo_learnning_py/limo_learnning_py/limo_server.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # -*- coding: utf-8 -*- 3 | 4 | import sys 5 | 6 | import rclpy 7 | from rclpy.node import Node 8 | from geometry_msgs.msg import Twist 9 | from limo_msgs.srv import LimoSrv 10 | 11 | class LimoServiceNode(Node): 12 | 13 | def __init__(self): 14 | super().__init__('limo_srv') 15 | 16 | # 创建一个速度命令发布者,发布到 /cmd_vel 话题,队列大小为10 17 | self.pub_vel = self.create_publisher(Twist, 'cmd_vel', 10) 18 | 19 | # 创建一个服务,服务名称为 "limo_srv" 20 | self.srv = self.create_service(LimoSrv, 'limo_srv', self.limo_srv_callback) 21 | 22 | self.count = 0 23 | self.vel_cmd = Twist() 24 | 25 | def limo_srv_callback(self, request, response): 26 | while rclpy.ok(): 27 | if self.count < 4: 28 | # 将请求的数据 赋值给vel_cmd 29 | self.vel_cmd.linear.x = request.x 30 | self.vel_cmd.linear.y = request.y 31 | self.vel_cmd.angular.z = request.z 32 | 33 | # 发布话题消息 34 | self.pub_vel.publish(self.vel_cmd) 35 | 36 | # 输出日志信息,提示已经完成话题发布 37 | self.get_logger().info(f'Publishing: linear.x: {self.vel_cmd.linear.x}, angular.z: {self.vel_cmd.angular.z}') 38 | 39 | rclpy.sleep(0.5) # 休眠500毫秒 40 | else: 41 | # 停止机器人 42 | self.vel_cmd.linear.x = 0.0 43 | self.vel_cmd.linear.y = 0.0 44 | self.vel_cmd.angular.z = 0.0 45 | 46 | # 发布话题消息 47 | self.pub_vel.publish(self.vel_cmd) 48 | 49 | # 输出日志信息,提示已经完成话题发布 50 | self.get_logger().info(f'Publishing: linear.x: {self.vel_cmd.linear.x}, angular.z: {self.vel_cmd.angular.z}') 51 | 52 | response.success = True 53 | break 54 | 55 | self.count += 1 56 | 57 | # 打印请求和响应的日志信息 58 | self.get_logger().info(f'request.x: {request.x}') 59 | self.get_logger().info(f'request.y: {request.y}') 60 | self.get_logger().info(f'request.z: {request.z}') 61 | self.get_logger().info(f'response.success.data: {response.success}') 62 | 63 | return response 64 | 65 | def main(args=None): 66 | rclpy.init(args=args) 67 | 68 | # 创建一个LimoServiceNode节点对象并进入循环,等待和处理ROS2消息 69 | node = LimoServiceNode() 70 | rclpy.spin(node) 71 | 72 | # 关闭ROS2 Python接口 73 | rclpy.shutdown() 74 | 75 | if __name__ == '__main__': 76 | main() 77 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/limo_learnning_py/limo_topic_cmd.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # -*- coding: utf-8 -*- 3 | 4 | import rclpy # 引入ROS2 Python接口库 5 | from rclpy.node import Node # 引入ROS2节点类 6 | from geometry_msgs.msg import Twist # 引入geometry_msgs消息类型中的Twist消息 7 | 8 | class LimoTopicCmd(Node): # 自定义一个LimoTopicCmd类并继承rclpy.Node 9 | def __init__(self): 10 | super().__init__('LimoTopicCmd') # 初始化节点名称为"LimoTopicCmd" 11 | 12 | # 创建速度命令发布者,发布到 /cmd_vel 话题,队列大小为10 13 | self.pub_vel = self.create_publisher(Twist, '/cmd_vel', 10) 14 | 15 | # 创建一个定时器,每500毫秒调用一次 timer_callback 函数 16 | self.timer = self.create_timer(0.5, self.timer_callback) 17 | 18 | self.count = 0 # 定义计数器 19 | 20 | def timer_callback(self): # 定义一个周期性执行的回调函数 21 | vel_cmd = Twist() # 创建一个Twist消息对象 22 | 23 | # 检查计数器次数 24 | if self.count < 4: 25 | # 填入速度信息 26 | vel_cmd.linear.x = 0.1 27 | vel_cmd.linear.y = 0.0 28 | vel_cmd.linear.z = 0.0 29 | vel_cmd.angular.z = 0.0 30 | # 发布话题消息 31 | self.pub_vel.publish(vel_cmd) 32 | else: 33 | # 停止机器人 34 | vel_cmd.linear.x = 0.0 35 | vel_cmd.linear.y = 0.0 36 | vel_cmd.linear.z = 0.0 37 | vel_cmd.angular.z = 0.0 38 | # 发布话题消息 39 | self.pub_vel.publish(vel_cmd) 40 | 41 | # 输出日志信息,提示已经完成话题发布 42 | self.get_logger().info(f'Publishing: linear.x: {vel_cmd.linear.x}, angular.z: {vel_cmd.angular.z}') 43 | 44 | self.count += 1 # 增加计数器 45 | 46 | def main(args=None): 47 | rclpy.init(args=args) # 初始化ROS2 Python接口 48 | 49 | # 创建一个LimoTopicCmd节点对象并进入循环,等待和处理ROS2消息 50 | node = LimoTopicCmd() 51 | rclpy.spin(node) 52 | 53 | # 关闭ROS2 Python接口 54 | rclpy.shutdown() 55 | 56 | if __name__ == '__main__': 57 | main() 58 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/limo_learnning_py/multi_goal_nav.py: -------------------------------------------------------------------------------- 1 | import rclpy 2 | from rclpy.node import Node 3 | from geometry_msgs.msg import PoseStamped 4 | from nav2_msgs.action import NavigateToPose 5 | from rclpy.action import ActionClient 6 | from rclpy.time import Time 7 | import tf_transformations 8 | import time 9 | 10 | class MultiGoalNavigator(Node): 11 | 12 | def __init__(self): 13 | super().__init__('multi_goal_navigator') 14 | 15 | # 创建一个目标点列表 16 | goals = [] 17 | # 填充目标点列表 (示例中使用两个目标点) 18 | goals.append(self.create_goal_pose(1.0, 1.0, 0.0)) 19 | goals.append(self.create_goal_pose(2.0, 2.0, 0.0)) 20 | 21 | # 导航到多个目标点 22 | for goal in goals: 23 | self.navigate_to_goal(goal) 24 | 25 | def create_goal_pose(self, x, y, yaw): 26 | goal = PoseStamped() 27 | goal.header.frame_id = 'map' 28 | goal.header.stamp = self.get_clock().now().to_msg() 29 | 30 | goal.pose.position.x = x 31 | goal.pose.position.y = y 32 | goal.pose.orientation = self.create_quaternion_from_yaw(yaw) 33 | 34 | return goal 35 | 36 | def create_quaternion_from_yaw(self, yaw): 37 | q = tf_transformations.quaternion_from_euler(0, 0, yaw) 38 | pose_orientation = PoseStamped() 39 | pose_orientation.pose.orientation.x = q[0] 40 | pose_orientation.pose.orientation.y = q[1] 41 | pose_orientation.pose.orientation.z = q[2] 42 | pose_orientation.pose.orientation.w = q[3] 43 | 44 | return pose_orientation.pose.orientation 45 | 46 | def navigate_to_goal(self, goal): 47 | nav_to_pose_client = ActionClient(self, NavigateToPose, 'navigate_to_pose') 48 | 49 | if not nav_to_pose_client.wait_for_server(timeout_sec=10.0): 50 | self.get_logger().error('Action server not available after waiting') 51 | return 52 | 53 | goal_msg = NavigateToPose.Goal() 54 | goal_msg.pose = goal 55 | 56 | self.get_logger().info('Navigating to goal...') 57 | 58 | future = nav_to_pose_client.send_goal_async(goal_msg) 59 | future.add_done_callback(self.goal_response_callback) 60 | 61 | rclpy.spin_until_future_complete(self, future) 62 | # 等待当前目标完成 63 | # rclpy.sleep(5) 64 | time.sleep(5) 65 | def goal_response_callback(self, future): 66 | goal_handle = future.result() 67 | if not goal_handle.accepted: 68 | self.get_logger().info('Goal rejected') 69 | return 70 | 71 | self.get_logger().info('Goal accepted') 72 | result_future = goal_handle.get_result_async() 73 | result_future.add_done_callback(self.get_result_callback) 74 | 75 | def get_result_callback(self, future): 76 | result = future.result().result 77 | self.get_logger().info(f'Goal result: {result}') 78 | 79 | 80 | def main(args=None): 81 | rclpy.init(args=args) 82 | node = MultiGoalNavigator() 83 | rclpy.spin(node) 84 | node.destroy_node() 85 | rclpy.shutdown() 86 | 87 | 88 | if __name__ == '__main__': 89 | main() 90 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | limo_learnning_py 5 | 0.0.0 6 | TODO: Package description 7 | agilex 8 | TODO: License declaration 9 | 10 | rclpy 11 | limo_msgs 12 | ament_copyright 13 | ament_flake8 14 | ament_pep257 15 | python3-pytest 16 | 17 | 18 | ament_python 19 | 20 | 21 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/resource/limo_learnning_py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/limo/limo_learnning_py/resource/limo_learnning_py -------------------------------------------------------------------------------- /limo/limo_learnning_py/setup.cfg: -------------------------------------------------------------------------------- 1 | [develop] 2 | script_dir=$base/lib/limo_learnning_py 3 | [install] 4 | install_scripts=$base/lib/limo_learnning_py 5 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import find_packages, setup 2 | 3 | package_name = 'limo_learnning_py' 4 | 5 | setup( 6 | name=package_name, 7 | version='0.0.0', 8 | packages=find_packages(exclude=['test']), 9 | data_files=[ 10 | ('share/ament_index/resource_index/packages', 11 | ['resource/' + package_name]), 12 | ('share/' + package_name, ['package.xml']), 13 | ], 14 | install_requires=['setuptools'], 15 | zip_safe=True, 16 | maintainer='agilex', 17 | maintainer_email='agilex@todo.todo', 18 | description='TODO: Package description', 19 | license='TODO: License declaration', 20 | tests_require=['pytest'], 21 | entry_points={ 22 | 'console_scripts': [ 23 | "limo_topic_cmd = limo_learnning_py.limo_topic_cmd:main", 24 | "limo_server = limo_learnning_py.limo_server:main", 25 | "limo_client = limo_learnning_py.limo_client:main", 26 | "limo_action_server = limo_learnning_py.limo_action_server:main", 27 | "limo_action_client = limo_learnning_py.limo_action_client:main", 28 | "limo_scan = limo_learnning_py.limo_scan:main", 29 | "multi_goal_nav = limo_learnning_py.multi_goal_nav:main" 30 | 31 | ], 32 | }, 33 | ) 34 | 35 | 36 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2015 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | # Remove the `skip` decorator once the source file(s) have a copyright header 20 | @pytest.mark.skip(reason='No copyright header has been placed in the generated source file.') 21 | @pytest.mark.copyright 22 | @pytest.mark.linter 23 | def test_copyright(): 24 | rc = main(argv=['.', 'test']) 25 | assert rc == 0, 'Found errors' 26 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /limo/limo_learnning_py/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2015 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /limo/limo_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(limo_msgs) 3 | 4 | if(NOT CMAKE_C_STANDARD) 5 | set(CMAKE_C_STANDARD 99) 6 | endif() 7 | 8 | # Default to C++14 9 | if(NOT CMAKE_CXX_STANDARD) 10 | set(CMAKE_CXX_STANDARD 14) 11 | endif() 12 | 13 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 14 | add_compile_options(-Wall -Wextra -Wpedantic) 15 | endif() 16 | 17 | # find dependencies 18 | find_package(ament_cmake REQUIRED) 19 | find_package(std_msgs REQUIRED) 20 | find_package(builtin_interfaces REQUIRED) 21 | find_package(rosidl_default_generators REQUIRED) 22 | 23 | rosidl_generate_interfaces(${PROJECT_NAME} 24 | "msg/LimoStatus.msg" 25 | "srv/LimoSrv.srv" 26 | "action/LimoAction.action" 27 | DEPENDENCIES 28 | builtin_interfaces std_msgs ) 29 | 30 | if(BUILD_TESTING) 31 | find_package(ament_lint_auto REQUIRED) 32 | ament_lint_auto_find_test_dependencies() 33 | endif() 34 | 35 | 36 | ament_package() 37 | -------------------------------------------------------------------------------- /limo/limo_msgs/action/LimoAction.action: -------------------------------------------------------------------------------- 1 | # LimoAction.action 2 | float32 x 3 | float32 y 4 | float32 z 5 | --- 6 | bool success 7 | --- 8 | uint32 status 9 | 10 | -------------------------------------------------------------------------------- /limo/limo_msgs/msg/LimoStatus.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | 3 | uint8 vehicle_state 4 | uint8 control_mode 5 | float64 battery_voltage 6 | uint16 error_code 7 | uint8 motion_mode -------------------------------------------------------------------------------- /limo/limo_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | limo_msgs 5 | 0.0.0 6 | message for limo base 7 | tx 8 | BSD 9 | 10 | ament_cmake 11 | 12 | std_msgs 13 | geometry_msgs 14 | 15 | rosidl_default_runtime 16 | rosidl_default_generators 17 | rosidl_interface_packages 18 | 19 | ament_lint_auto 20 | ament_lint_common 21 | 22 | 23 | 24 | ament_cmake 25 | 26 | 27 | -------------------------------------------------------------------------------- /limo/limo_msgs/srv/LimoSrv.srv: -------------------------------------------------------------------------------- 1 | # LimoSrv.srv 2 | float32 x 3 | float32 y 4 | float32 z 5 | --- 6 | bool success 7 | -------------------------------------------------------------------------------- /piper/README.md: -------------------------------------------------------------------------------- 1 | # Moveit2环境配置 2 | 3 | ## 1、安装Moveit2 4 | 5 | 1)二进制安装,[参考链接](https://moveit.ai/install-moveit2/binary/) 6 | 7 | ``` 8 | sudo apt install ros-humble-moveit* 9 | ``` 10 | 11 | 2)源码编译方法,[参考链接](https://moveit.ai/install-moveit2/source/) 12 | 13 | ## 2、使用环境 14 | 15 | 安装完Moveit2之后,需要安装一些依赖 16 | 17 | ``` 18 | sudo apt-get install ros-humble-control* ros-humble-joint-trajectory-controller ros-humble-joint-state-* ros-humble-gripper-controllers ros-humble-trajectory-msgs 19 | ``` 20 | 21 | ## 3、使用方法 22 | 23 | 1)查看piper机械臂模型 24 | 25 | ``` 26 | ros2 launch piper_description display_piper.launch.py 27 | ``` 28 | 29 | 成功打开之后,需要在Rviz中添加模型,成功添加之后 30 | 31 | ![](image/piper.png) 32 | 33 | 34 | 35 | 2)使用moveit2,控制机械臂 36 | 37 | ``` 38 | ros2 launch piper_moveit_config_v5 demo.launch.py 39 | ``` 40 | 41 | ![](image/piper_moveit.png) 42 | 43 | 44 | 45 | ## 4、启动Gazebo仿真 46 | 47 | 1)启动Gazebo仿真 48 | 49 | ``` 50 | ros2 launch piper_description piper_gazebo.launch.py 51 | ``` 52 | 53 | ![](image/piper_gazebo.png) 54 | 55 | 2)使用moveit2,控制机械臂 56 | 57 | > 注:有时候会出现moveit控制不了gazebo模型的情况,需要重新启动 58 | 59 | ``` 60 | ros2 launch piper_moveit_config_v4 demo.launch.py 61 | ``` 62 | 63 | ![](image/piper_gazebo_moveit.png) 64 | 65 | -------------------------------------------------------------------------------- /piper/image/piper.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/image/piper.png -------------------------------------------------------------------------------- /piper/image/piper_gazebo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/image/piper_gazebo.png -------------------------------------------------------------------------------- /piper/image/piper_gazebo_moveit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/image/piper_gazebo_moveit.png -------------------------------------------------------------------------------- /piper/image/piper_moveit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/image/piper_moveit.png -------------------------------------------------------------------------------- /piper/learnning_piper/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.8) 2 | project(learnning_piper) 3 | 4 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 5 | add_compile_options(-Wall -Wextra -Wpedantic) 6 | endif() 7 | 8 | # find dependencies 9 | find_package(ament_cmake REQUIRED) 10 | find_package(rclcpp REQUIRED) 11 | find_package(geometry_msgs REQUIRED) 12 | find_package(moveit_msgs REQUIRED) 13 | find_package(moveit_core REQUIRED) 14 | find_package(moveit_ros_planning REQUIRED) 15 | find_package(moveit_ros_planning_interface REQUIRED) 16 | find_package(moveit_servo REQUIRED) 17 | find_package(moveit_visual_tools REQUIRED) 18 | 19 | 20 | add_executable(move_target src/move_target.cpp) 21 | ament_target_dependencies( 22 | move_target 23 | geometry_msgs 24 | rclcpp 25 | moveit_msgs 26 | moveit_core 27 | moveit_ros_planning 28 | moveit_ros_planning_interface 29 | moveit_visual_tools 30 | moveit_servo 31 | ) 32 | 33 | add_executable(move_multi_target src/move_multi_target.cpp) 34 | ament_target_dependencies( 35 | move_multi_target 36 | geometry_msgs 37 | rclcpp 38 | moveit_msgs 39 | moveit_core 40 | moveit_ros_planning 41 | moveit_ros_planning_interface 42 | moveit_visual_tools 43 | moveit_servo 44 | ) 45 | 46 | add_executable(moveit_cpp_tutorial src/moveit_cpp_tutorial.cpp) 47 | ament_target_dependencies( 48 | moveit_cpp_tutorial 49 | geometry_msgs 50 | rclcpp 51 | moveit_msgs 52 | moveit_core 53 | moveit_ros_planning 54 | moveit_ros_planning_interface 55 | moveit_visual_tools 56 | moveit_servo 57 | ) 58 | 59 | install(TARGETS 60 | move_target 61 | move_multi_target 62 | moveit_cpp_tutorial 63 | DESTINATION 64 | lib/${PROJECT_NAME}) 65 | 66 | 67 | if(BUILD_TESTING) 68 | find_package(ament_lint_auto REQUIRED) 69 | # the following line skips the linter which checks for copyrights 70 | # comment the line when a copyright and license is added to all source files 71 | set(ament_cmake_copyright_FOUND TRUE) 72 | # the following line skips cpplint (only works in a git repo) 73 | # comment the line when this package is in a git repo and when 74 | # a copyright and license is added to all source files 75 | set(ament_cmake_cpplint_FOUND TRUE) 76 | ament_lint_auto_find_test_dependencies() 77 | endif() 78 | 79 | ament_package() 80 | -------------------------------------------------------------------------------- /piper/learnning_piper/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | learnning_piper 5 | 0.0.0 6 | TODO: Package description 7 | agilex 8 | TODO: License declaration 9 | 10 | ament_cmake 11 | 12 | rclcpp 13 | moveit_core 14 | moveit_ros_perception 15 | moveit_ros_planning_interface 16 | moveit_servo 17 | moveit_hybrid_planning 18 | moveit_ros_planning 19 | moveit_msgs 20 | 21 | 22 | ament_lint_auto 23 | ament_lint_common 24 | 25 | 26 | ament_cmake 27 | 28 | 29 | -------------------------------------------------------------------------------- /piper/learnning_piper/src/move_multi_target.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | #include 5 | #include 6 | 7 | int main(int argc, char *argv[]) 8 | { 9 | // 初始化 ROS 并创建节点 10 | rclcpp::init(argc, argv); 11 | auto const node = std::make_shared( 12 | "move_multi_target", 13 | rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true)); 14 | 15 | // 创建 ROS 日志器 16 | auto const logger = rclcpp::get_logger("move_multi_target"); 17 | 18 | // 创建 MoveIt MoveGroup 接口,用于与机械臂交互 19 | using moveit::planning_interface::MoveGroupInterface; 20 | auto move_group_interface = MoveGroupInterface(node, "arm"); 21 | 22 | // 定义多个目标位姿,每个位姿都通过 lambda 函数进行初始化 23 | std::vector target_poses = { 24 | [] { 25 | geometry_msgs::msg::Pose msg; 26 | msg.orientation.w = 1.0; // 设置姿态四元数的 w 分量(无旋转) 27 | msg.position.x = 0.28; // 设置目标位置的 x 坐标 28 | msg.position.y = -0.2; // 设置目标位置的 y 坐标 29 | msg.position.z = 0.5; // 设置目标位置的 z 坐标 30 | return msg; 31 | }(), 32 | [] { 33 | geometry_msgs::msg::Pose msg; 34 | msg.orientation.w = 1.0; 35 | msg.position.x = 0.27; 36 | msg.position.y = 0.2; 37 | msg.position.z = 0.5; 38 | return msg; 39 | }() 40 | }; 41 | 42 | // 遍历每个目标位姿,依次规划和执行 43 | for (const auto &target_pose : target_poses) 44 | { 45 | // 设置当前的目标位姿 46 | move_group_interface.setPoseTarget(target_pose); 47 | 48 | // 创建规划到目标位姿的路径 49 | auto const [success, plan] = [&move_group_interface] 50 | { 51 | moveit::planning_interface::MoveGroupInterface::Plan msg; // 定义一个空的规划消息 52 | auto const ok = static_cast(move_group_interface.plan(msg)); // 生成规划并检查是否成功 53 | return std::make_pair(ok, msg); // 返回是否成功以及规划的消息 54 | }(); 55 | 56 | // 如果规划成功,执行该路径 57 | if (success) 58 | { 59 | RCLCPP_INFO(logger, "Executing plan to target..."); // 输出执行规划的日志信息 60 | move_group_interface.execute(plan); // 执行规划的路径 61 | 62 | // 等待机械臂完成运动 63 | rclcpp::sleep_for(std::chrono::seconds(1)); 64 | 65 | RCLCPP_INFO(logger, "Target pose reached!"); // 目标点达到后输出日志信息 66 | } 67 | else 68 | { 69 | RCLCPP_ERROR(logger, "Planning to target failed!"); // 如果规划失败,输出错误日志信息 70 | break; // 如果某个目标点的规划失败,退出循环,停止后续目标点的执行 71 | } 72 | 73 | // 可选:在每次执行完路径后暂停一会,或提示用户继续 74 | // rclcpp::sleep_for(std::chrono::seconds(1)); 75 | } 76 | 77 | // 关闭 ROS 78 | rclcpp::shutdown(); 79 | return 0; 80 | } 81 | -------------------------------------------------------------------------------- /piper/learnning_piper/src/move_target.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #include 4 | #include 5 | 6 | int main(int argc, char *argv[]) 7 | { 8 | // 初始化 ROS 并创建节点 9 | rclcpp::init(argc, argv); 10 | auto const node = std::make_shared( 11 | "move_target", // 节点名称为 "move_target" 12 | rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true)); // 自动声明参数,允许从命令行或文件中覆盖 13 | 14 | // 创建 ROS 日志器 15 | auto const logger = rclcpp::get_logger("move_target"); // 日志器,用于输出日志信息 16 | 17 | // 创建 MoveIt MoveGroup 接口 18 | using moveit::planning_interface::MoveGroupInterface; 19 | auto move_group_interface = MoveGroupInterface(node, "arm"); // "arm" 是规划组的名称 20 | 21 | // 设置目标位姿 22 | auto const target_pose = [] 23 | { 24 | geometry_msgs::msg::Pose msg; // 定义目标位姿的消息 25 | msg.orientation.w = 1.0; // 设置姿态的四元数,表示无旋转 26 | msg.position.x = 0.28; // 设置目标位置的 x 坐标 27 | msg.position.y = -0.2; // 设置目标位置的 y 坐标 28 | msg.position.z = 0.5; // 设置目标位置的 z 坐标 29 | 30 | return msg; // 返回目标位姿 31 | }(); 32 | move_group_interface.setPoseTarget(target_pose); // 将目标位姿设置为 MoveGroup 的目标 33 | 34 | // 生成到目标位姿的规划 35 | auto const [success, plan] = [&move_group_interface] 36 | { 37 | moveit::planning_interface::MoveGroupInterface::Plan msg; // 创建规划消息对象 38 | auto const ok = static_cast(move_group_interface.plan(msg)); // 调用规划函数,并检查是否成功 39 | return std::make_pair(ok, msg); // 返回规划是否成功及规划消息 40 | }(); 41 | 42 | // 如果规划成功,执行路径 43 | if (success) 44 | { 45 | move_group_interface.execute(plan); // 执行规划路径 46 | } 47 | else 48 | { 49 | RCLCPP_ERROR(logger, "Planning failed!"); // 如果规划失败,输出错误日志信息 50 | } 51 | 52 | // 关闭 ROS 53 | rclcpp::shutdown(); 54 | return 0; 55 | } 56 | -------------------------------------------------------------------------------- /piper/piper_description/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(piper_description) 3 | 4 | # Default to C99 5 | if(NOT CMAKE_C_STANDARD) 6 | set(CMAKE_C_STANDARD 99) 7 | endif() 8 | 9 | # Default to C++14 10 | if(NOT CMAKE_CXX_STANDARD) 11 | set(CMAKE_CXX_STANDARD 14) 12 | endif() 13 | 14 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 15 | add_compile_options(-Wall -Wextra -Wpedantic) 16 | endif() 17 | 18 | # find dependencies 19 | find_package(ament_cmake REQUIRED) 20 | # uncomment the following section in order to fill in 21 | # further dependencies manually. 22 | # find_package( REQUIRED) 23 | install( 24 | DIRECTORY launch meshes rviz urdf worlds 25 | DESTINATION share/${PROJECT_NAME} 26 | ) 27 | if(BUILD_TESTING) 28 | find_package(ament_lint_auto REQUIRED) 29 | # the following line skips the linter which checks for copyrights 30 | # uncomment the line when a copyright and license is not present in all source files 31 | #set(ament_cmake_copyright_FOUND TRUE) 32 | # the following line skips cpplint (only works in a git repo) 33 | # uncomment the line when this package is not in a git repo 34 | #set(ament_cmake_cpplint_FOUND TRUE) 35 | ament_lint_auto_find_test_dependencies() 36 | endif() 37 | 38 | ament_package() 39 | -------------------------------------------------------------------------------- /piper/piper_description/config/joint_name_piper_description.yaml: -------------------------------------------------------------------------------- 1 | # This config file is used by ros2_control 2 | controller_manager: 3 | ros__parameters: 4 | update_rate: 100 # Hz 5 | 6 | arm_controller: 7 | type: joint_trajectory_controller/JointTrajectoryController 8 | 9 | 10 | gripper_controller: 11 | type: joint_trajectory_controller/JointTrajectoryController 12 | 13 | 14 | joint_state_broadcaster: 15 | type: joint_state_broadcaster/JointStateBroadcaster 16 | 17 | arm_controller: 18 | ros__parameters: 19 | joints: 20 | - joint1 21 | - joint2 22 | - joint3 23 | - joint4 24 | - joint5 25 | - joint6 26 | command_interfaces: 27 | - position 28 | state_interfaces: 29 | - position 30 | - velocity 31 | gripper_controller: 32 | ros__parameters: 33 | joints: 34 | - joint7 35 | - joint8 36 | command_interfaces: 37 | - position 38 | state_interfaces: 39 | - position 40 | - velocity -------------------------------------------------------------------------------- /piper/piper_description/config/joint_names_agx_arm_description.yaml: -------------------------------------------------------------------------------- 1 | controller_joint_names: ['', 'joint1', 'joint2', 'joint3', 'joint4', 'joint5', 'joint6', 'joint7', 'joint8', ] 2 | -------------------------------------------------------------------------------- /piper/piper_description/config/piper_gazebo_control.yaml: -------------------------------------------------------------------------------- 1 | piper_description: 2 | joint_state_controller: 3 | type: joint_state_controller/JointStateController 4 | publish_rate: 200 5 | 6 | joint1_position_controller: 7 | type: position_controllers/JointPositionController 8 | joint: joint1 9 | pid: {p: 100.0, i: 0.01, d: 5.0} 10 | joint2_position_controller: 11 | type: position_controllers/JointPositionController 12 | joint: joint2 13 | pid: {p: 100.0, i: 0.01, d: 5.0} 14 | joint3_position_controller: 15 | type: position_controllers/JointPositionController 16 | joint: joint3 17 | pid: {p: 100.0, i: 0.01, d: 5.0} 18 | joint4_position_controller: 19 | type: position_controllers/JointPositionController 20 | joint: joint4 21 | pid: {p: 100.0, i: 0.01, d: 5.0} 22 | joint5_position_controller: 23 | type: position_controllers/JointPositionController 24 | joint: joint5 25 | pid: {p: 100.0, i: 0.01, d: 5.0} 26 | joint6_position_controller: 27 | type: position_controllers/JointPositionController 28 | joint: joint6 29 | pid: {p: 100.0, i: 0.01, d: 5.0} 30 | joint7_position_controller: 31 | type: position_controllers/JointPositionController 32 | joint: joint7 33 | pid: {p: 100, i: 0.001, d: 10.0} 34 | joint8_position_controller: 35 | type: position_controllers/JointPositionController 36 | joint: joint8 37 | pid: {p: 100, i: 0.001, d: 10.0} 38 | -------------------------------------------------------------------------------- /piper/piper_description/launch/display_piper.launch.py: -------------------------------------------------------------------------------- 1 | from ament_index_python.packages import get_package_share_path 2 | 3 | from launch import LaunchDescription 4 | from launch.actions import DeclareLaunchArgument 5 | from launch.conditions import IfCondition, UnlessCondition 6 | from launch.substitutions import Command, LaunchConfiguration 7 | 8 | from launch_ros.actions import Node 9 | from launch_ros.parameter_descriptions import ParameterValue 10 | 11 | def generate_launch_description(): 12 | urdf_tutorial_path = get_package_share_path('piper_description') 13 | default_model_path = urdf_tutorial_path / 'urdf/piper_description.xacro' 14 | default_rviz_config_path = urdf_tutorial_path / 'rviz/rviz.rviz' 15 | 16 | gui_arg = DeclareLaunchArgument(name='gui', default_value='true', choices=['true', 'false'], 17 | description='Flag to enable joint_state_publisher_gui') 18 | model_arg = DeclareLaunchArgument(name='model', default_value=str(default_model_path), 19 | description='Absolute path to robot urdf file') 20 | rviz_arg = DeclareLaunchArgument(name='rvizconfig', default_value=str(default_rviz_config_path), 21 | description='Absolute path to rviz config file') 22 | 23 | robot_description = ParameterValue(Command(['xacro ', LaunchConfiguration('model')]), 24 | value_type=str) 25 | 26 | robot_state_publisher_node = Node( 27 | package='robot_state_publisher', 28 | executable='robot_state_publisher', 29 | parameters=[{'robot_description': robot_description}] 30 | ) 31 | 32 | # Depending on gui parameter, either launch joint_state_publisher or joint_state_publisher_gui 33 | joint_state_publisher_node = Node( 34 | package='joint_state_publisher', 35 | executable='joint_state_publisher', 36 | condition=UnlessCondition(LaunchConfiguration('gui')) 37 | ) 38 | 39 | joint_state_publisher_gui_node = Node( 40 | package='joint_state_publisher_gui', 41 | executable='joint_state_publisher_gui', 42 | condition=IfCondition(LaunchConfiguration('gui')) 43 | ) 44 | 45 | rviz_node = Node( 46 | package='rviz2', 47 | executable='rviz2', 48 | name='rviz2', 49 | output='screen', 50 | arguments=['-d', LaunchConfiguration('rvizconfig')], 51 | ) 52 | 53 | return LaunchDescription([ 54 | gui_arg, 55 | model_arg, 56 | rviz_arg, 57 | joint_state_publisher_node, 58 | joint_state_publisher_gui_node, 59 | robot_state_publisher_node, 60 | rviz_node 61 | ]) -------------------------------------------------------------------------------- /piper/piper_description/launch/piper_gazebo.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | 3 | from ament_index_python.packages import get_package_share_directory 4 | from launch import LaunchDescription 5 | from launch.actions import IncludeLaunchDescription 6 | from launch.launch_description_sources import PythonLaunchDescriptionSource 7 | 8 | 9 | def generate_launch_description(): 10 | 11 | gazebo_world_path = os.path.join( 12 | get_package_share_directory('piper_description'), 'worlds', 'world_v1.world') 13 | 14 | gazebo_options_dict = { 15 | 'world': gazebo_world_path, 16 | 'verbose': 'true' 17 | } 18 | 19 | gazebo_simulator = IncludeLaunchDescription( 20 | PythonLaunchDescriptionSource([ 21 | os.path.join(get_package_share_directory('gazebo_ros'), 'launch', 'gazebo.launch.py') 22 | ]), 23 | launch_arguments=gazebo_options_dict.items() 24 | ) 25 | 26 | car_sim_options = { 27 | 'start_x': '0', 28 | 'start_y': '0', 29 | 'start_z': '0', 30 | 'start_yaw': '0', 31 | 'pub_tf': 'true', 32 | 'tf_freq': '100.0', 33 | 'blue': 'false' 34 | } 35 | 36 | spawn_car = IncludeLaunchDescription( 37 | PythonLaunchDescriptionSource([ 38 | os.path.join( 39 | get_package_share_directory('piper_description'), 40 | 'launch', 'piper_spawn.launch.py') 41 | ]), 42 | launch_arguments=car_sim_options.items() 43 | ) 44 | 45 | return LaunchDescription([ 46 | gazebo_simulator, 47 | spawn_car, 48 | ]) 49 | -------------------------------------------------------------------------------- /piper/piper_description/launch/piper_spawn.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | 3 | from launch import LaunchDescription 4 | from launch.actions import DeclareLaunchArgument 5 | from launch.actions import SetEnvironmentVariable 6 | from launch.substitutions import Command, LaunchConfiguration 7 | from launch_ros.actions import Node 8 | from launch_ros.substitutions import FindPackageShare 9 | import launch_ros.descriptions 10 | import launch_ros 11 | import launch 12 | 13 | 14 | def generate_launch_description(): 15 | pkg_share = FindPackageShare(package='piper_description').find('piper_description') 16 | urdf_file = os.path.join(pkg_share, 'urdf/piper_description_gazebo.xacro') 17 | 18 | SetEnvironmentVariable('GAZEBO_MODEL_PATH', pkg_share) 19 | 20 | return LaunchDescription([ 21 | DeclareLaunchArgument('start_x', default_value='0.0', 22 | description='X coordinate of starting position'), 23 | DeclareLaunchArgument('start_y', default_value='0.0', 24 | description='Y coordinate of starting position'), 25 | DeclareLaunchArgument('start_z', default_value='0.0', 26 | description='Z coordinate of starting position'), 27 | DeclareLaunchArgument('start_yaw', default_value='0.0', 28 | description='Yaw angle of starting orientation'), 29 | DeclareLaunchArgument('robot_name', default_value='', 30 | description='Name and prefix for this robot'), 31 | Node( 32 | package='robot_state_publisher', 33 | executable='robot_state_publisher', 34 | name='robot_state_publisher', 35 | output='screen', 36 | # parameters=[{ 37 | # 'use_sim_time': True, 38 | # 'robot_description': Command( 39 | # [f'xacro {urdf_file}', ' robot_name:=', LaunchConfiguration('robot_name')]) 40 | parameters=[{ 41 | 'use_sim_time': True, 42 | 'robot_description': launch_ros.descriptions.ParameterValue( launch.substitutions.Command([ 43 | 'xacro ',os.path.join(pkg_share,urdf_file)]), value_type=str) }] 44 | ), 45 | Node( 46 | package='gazebo_ros', 47 | executable='spawn_entity.py', 48 | arguments=[ 49 | '-entity', LaunchConfiguration('robot_name'), 50 | '-topic', 'robot_description', 51 | '-x', LaunchConfiguration('start_x'), 52 | '-y', LaunchConfiguration('start_y'), 53 | '-z', LaunchConfiguration('start_z'), 54 | '-Y', LaunchConfiguration('start_yaw'), 55 | '-timeout', '1000' 56 | ], 57 | output='screen') 58 | ]) 59 | -------------------------------------------------------------------------------- /piper/piper_description/meshes/base_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/piper_description/meshes/base_link.STL -------------------------------------------------------------------------------- /piper/piper_description/meshes/link1.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/piper_description/meshes/link1.STL -------------------------------------------------------------------------------- /piper/piper_description/meshes/link2.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/piper_description/meshes/link2.STL -------------------------------------------------------------------------------- /piper/piper_description/meshes/link3.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/piper_description/meshes/link3.STL -------------------------------------------------------------------------------- /piper/piper_description/meshes/link4.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/piper_description/meshes/link4.STL -------------------------------------------------------------------------------- /piper/piper_description/meshes/link5.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/piper_description/meshes/link5.STL -------------------------------------------------------------------------------- /piper/piper_description/meshes/link6.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/piper_description/meshes/link6.STL -------------------------------------------------------------------------------- /piper/piper_description/meshes/link7.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/piper_description/meshes/link7.STL -------------------------------------------------------------------------------- /piper/piper_description/meshes/link8.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/agilexrobotics/agilex_open_class/8e799754af623c3cec954b74b186d63d6ce8fa62/piper/piper_description/meshes/link8.STL -------------------------------------------------------------------------------- /piper/piper_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | piper_description 5 | 0.0.0 6 | TODO: Package description 7 | q 8 | TODO: License declaration 9 | 10 | ament_cmake 11 | ament_cmake 12 | joint_state_publisher 13 | joint_state_publisher_gui 14 | 15 | 16 | rviz2 17 | xacro 18 | 19 | ament_lint_auto 20 | ament_lint_common 21 | 22 | 23 | ament_cmake 24 | 25 | 26 | -------------------------------------------------------------------------------- /piper/piper_description/worlds/empty.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | model://sun 7 | 8 | 9 | 10 | 11 | model://ground_plane 12 | 13 | 14 | 15 | 16 | 0.01 17 | 1 18 | 100 19 | 0 0 -9.8 20 | 21 | 22 | quick 23 | 500 24 | 1.3 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | urdf: 3 | package: piper_description 4 | relative_path: urdf/piper_description.xacro 5 | srdf: 6 | relative_path: config/piper.srdf 7 | package_settings: 8 | author_name: agx 9 | author_email: agilex@agilex.ai 10 | generated_timestamp: 1726643166 11 | control_xacro: 12 | command: 13 | - position 14 | state: 15 | - position 16 | - velocity 17 | modified_urdf: 18 | xacros: 19 | - control_xacro 20 | control_xacro: 21 | command: 22 | - position 23 | state: 24 | - position 25 | - velocity -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.22) 2 | project(piper_moveit_config_v4) 3 | 4 | find_package(ament_cmake REQUIRED) 5 | 6 | ament_package() 7 | 8 | install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} 9 | PATTERN "setup_assistant.launch" EXCLUDE) 10 | install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) 11 | install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) 12 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/config/initial_positions.yaml: -------------------------------------------------------------------------------- 1 | # Default initial positions for piper's ros2_control fake system 2 | 3 | initial_positions: 4 | joint1: 0 5 | joint2: 0 6 | joint3: 0 7 | joint4: 0 8 | joint5: 0 9 | joint6: 0 10 | joint7: 0 11 | joint8: 0 -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/config/joint_limits.yaml: -------------------------------------------------------------------------------- 1 | # joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed 2 | 3 | # For beginners, we downscale velocity and acceleration limits. 4 | # You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. 5 | default_velocity_scaling_factor: 0.1 6 | default_acceleration_scaling_factor: 0.1 7 | 8 | # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] 9 | # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] 10 | joint_limits: 11 | joint1: 12 | has_velocity_limits: true 13 | max_velocity: 1.6199300000000001 14 | has_acceleration_limits: false 15 | max_acceleration: 0 16 | joint2: 17 | has_velocity_limits: true 18 | max_velocity: 1.6199300000000001 19 | has_acceleration_limits: false 20 | max_acceleration: 0 21 | joint3: 22 | has_velocity_limits: true 23 | max_velocity: 1.6199300000000001 24 | has_acceleration_limits: false 25 | max_acceleration: 0 26 | joint4: 27 | has_velocity_limits: true 28 | max_velocity: 1.6199300000000001 29 | has_acceleration_limits: false 30 | max_acceleration: 0 31 | joint5: 32 | has_velocity_limits: true 33 | max_velocity: 1.6199300000000001 34 | has_acceleration_limits: false 35 | max_acceleration: 0 36 | joint6: 37 | has_velocity_limits: true 38 | max_velocity: 1.6199300000000001 39 | has_acceleration_limits: false 40 | max_acceleration: 0 41 | joint7: 42 | has_velocity_limits: true 43 | max_velocity: 1.6199300000000001 44 | has_acceleration_limits: false 45 | max_acceleration: 0 46 | joint8: 47 | has_velocity_limits: true 48 | max_velocity: 1.6199300000000001 49 | has_acceleration_limits: false 50 | max_acceleration: 0 -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | arm: 2 | kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin 3 | kinematics_solver_search_resolution: 0.0050000000000000001 4 | kinematics_solver_timeout: 0.0050000000000000001 -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/config/moveit.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz_common/Displays 3 | Name: Displays 4 | Property Tree Widget: 5 | Expanded: 6 | - /MotionPlanning1 7 | - Class: rviz_common/Help 8 | Name: Help 9 | - Class: rviz_common/Views 10 | Name: Views 11 | Visualization Manager: 12 | Displays: 13 | - Class: rviz_default_plugins/Grid 14 | Name: Grid 15 | Value: true 16 | - Class: moveit_rviz_plugin/MotionPlanning 17 | Name: MotionPlanning 18 | Planned Path: 19 | Loop Animation: true 20 | State Display Time: 0.05 s 21 | Trajectory Topic: display_planned_path 22 | Planning Scene Topic: monitored_planning_scene 23 | Robot Description: robot_description 24 | Scene Geometry: 25 | Scene Alpha: 1 26 | Scene Robot: 27 | Robot Alpha: 0.5 28 | Value: true 29 | Global Options: 30 | Fixed Frame: world 31 | Tools: 32 | - Class: rviz_default_plugins/Interact 33 | - Class: rviz_default_plugins/MoveCamera 34 | - Class: rviz_default_plugins/Select 35 | Value: true 36 | Views: 37 | Current: 38 | Class: rviz_default_plugins/Orbit 39 | Distance: 2.0 40 | Focal Point: 41 | X: -0.1 42 | Y: 0.25 43 | Z: 0.30 44 | Name: Current View 45 | Pitch: 0.5 46 | Target Frame: world 47 | Yaw: -0.623 48 | Window Geometry: 49 | Height: 975 50 | QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 51 | Width: 1200 52 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/config/moveit_controllers.yaml: -------------------------------------------------------------------------------- 1 | # MoveIt uses this configuration for controller management 2 | 3 | moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager 4 | 5 | moveit_simple_controller_manager: 6 | controller_names: 7 | - arm_controller 8 | - gripper_controller 9 | 10 | arm_controller: 11 | type: FollowJointTrajectory 12 | action_ns: follow_joint_trajectory 13 | default: true 14 | joints: 15 | - joint1 16 | - joint2 17 | - joint3 18 | - joint4 19 | - joint5 20 | - joint6 21 | gripper_controller: 22 | type: FollowJointTrajectory 23 | joints: 24 | - joint7 25 | - joint8 26 | action_ns: follow_joint_trajectory 27 | default: true -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/config/pilz_cartesian_limits.yaml: -------------------------------------------------------------------------------- 1 | # Limits for the Pilz planner 2 | cartesian_limits: 3 | max_trans_vel: 1.0 4 | max_trans_acc: 2.25 5 | max_trans_dec: -5.0 6 | max_rot_vel: 1.57 7 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/config/piper.ros2_control.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | mock_components/GenericSystem 10 | 11 | 12 | 13 | 14 | ${initial_positions['joint1']} 15 | 16 | 17 | 18 | 19 | 20 | 21 | ${initial_positions['joint2']} 22 | 23 | 24 | 25 | 26 | 27 | 28 | ${initial_positions['joint3']} 29 | 30 | 31 | 32 | 33 | 34 | 35 | ${initial_positions['joint4']} 36 | 37 | 38 | 39 | 40 | 41 | 42 | ${initial_positions['joint5']} 43 | 44 | 45 | 46 | 47 | 48 | 49 | ${initial_positions['joint6']} 50 | 51 | 52 | 53 | 54 | 55 | 56 | ${initial_positions['joint7']} 57 | 58 | 59 | 60 | 61 | 62 | 63 | ${initial_positions['joint8']} 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/config/piper.srdf: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/config/piper.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/config/ros2_controllers.yaml: -------------------------------------------------------------------------------- 1 | # This config file is used by ros2_control 2 | controller_manager: 3 | ros__parameters: 4 | update_rate: 100 # Hz 5 | 6 | arm_controller: 7 | type: joint_trajectory_controller/JointTrajectoryController 8 | 9 | 10 | gripper_controller: 11 | type: joint_trajectory_controller/JointTrajectoryController 12 | 13 | 14 | joint_state_broadcaster: 15 | type: joint_state_broadcaster/JointStateBroadcaster 16 | 17 | arm_controller: 18 | ros__parameters: 19 | joints: 20 | - joint1 21 | - joint2 22 | - joint3 23 | - joint4 24 | - joint5 25 | - joint6 26 | command_interfaces: 27 | - position 28 | state_interfaces: 29 | - position 30 | - velocity 31 | gripper_controller: 32 | ros__parameters: 33 | joints: 34 | - joint7 35 | - joint8 36 | command_interfaces: 37 | - position 38 | state_interfaces: 39 | - position 40 | - velocity -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/launch/demo.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_demo_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v4").to_moveit_configs() 7 | return generate_demo_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/launch/move_group.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_move_group_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v4").to_moveit_configs() 7 | return generate_move_group_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/launch/moveit_rviz.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_moveit_rviz_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v4").to_moveit_configs() 7 | return generate_moveit_rviz_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/launch/rsp.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_rsp_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v4").to_moveit_configs() 7 | return generate_rsp_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/launch/setup_assistant.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_setup_assistant_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v4").to_moveit_configs() 7 | return generate_setup_assistant_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/launch/spawn_controllers.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_spawn_controllers_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v4").to_moveit_configs() 7 | return generate_spawn_controllers_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/launch/static_virtual_joint_tfs.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v4").to_moveit_configs() 7 | return generate_static_virtual_joint_tfs_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/launch/warehouse_db.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_warehouse_db_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v4").to_moveit_configs() 7 | return generate_warehouse_db_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v4/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | piper_moveit_config_v4 5 | 0.3.0 6 | 7 | An automatically generated package with all the configuration and launch files for using the piper with the MoveIt Motion Planning Framework 8 | 9 | agx 10 | 11 | BSD 12 | 13 | http://moveit.ros.org/ 14 | https://github.com/ros-planning/moveit2/issues 15 | https://github.com/ros-planning/moveit2 16 | 17 | agx 18 | 19 | ament_cmake 20 | 21 | moveit_ros_move_group 22 | moveit_kinematics 23 | moveit_planners 24 | moveit_simple_controller_manager 25 | joint_state_publisher 26 | joint_state_publisher_gui 27 | tf2_ros 28 | xacro 29 | 31 | 32 | 33 | controller_manager 34 | moveit_configs_utils 35 | moveit_ros_move_group 36 | moveit_ros_visualization 37 | moveit_ros_warehouse 38 | moveit_setup_assistant 39 | piper_description 40 | robot_state_publisher 41 | rviz2 42 | rviz_common 43 | rviz_default_plugins 44 | tf2_ros 45 | warehouse_ros_mongo 46 | xacro 47 | 48 | 49 | 50 | ament_cmake 51 | 52 | 53 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | urdf: 3 | package: piper_description 4 | relative_path: urdf/piper_description.xacro 5 | srdf: 6 | relative_path: config/piper.srdf 7 | package_settings: 8 | author_name: agilex 9 | author_email: agilex@agilex.ai 10 | generated_timestamp: 1726746430 11 | control_xacro: 12 | command: 13 | - position 14 | state: 15 | - position 16 | - velocity 17 | modified_urdf: 18 | xacros: 19 | - control_xacro 20 | control_xacro: 21 | command: 22 | - position 23 | state: 24 | - position 25 | - velocity -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.22) 2 | project(piper_moveit_config_v5) 3 | 4 | find_package(ament_cmake REQUIRED) 5 | 6 | ament_package() 7 | 8 | install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} 9 | PATTERN "setup_assistant.launch" EXCLUDE) 10 | install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) 11 | install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) 12 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/config/initial_positions.yaml: -------------------------------------------------------------------------------- 1 | # Default initial positions for piper's ros2_control fake system 2 | 3 | initial_positions: 4 | joint1: 0 5 | joint2: 0 6 | joint3: 0 7 | joint4: 0 8 | joint5: 0 9 | joint6: 0 10 | joint7: 0 11 | joint8: 0 -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/config/joint_limits.yaml: -------------------------------------------------------------------------------- 1 | # joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed 2 | 3 | # For beginners, we downscale velocity and acceleration limits. 4 | # You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. 5 | default_velocity_scaling_factor: 0.1 6 | default_acceleration_scaling_factor: 0.1 7 | 8 | # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] 9 | # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] 10 | joint_limits: 11 | joint1: 12 | has_velocity_limits: true 13 | max_velocity: 1.6199300000000001 14 | has_acceleration_limits: false 15 | max_acceleration: 0 16 | joint2: 17 | has_velocity_limits: true 18 | max_velocity: 1.6199300000000001 19 | has_acceleration_limits: false 20 | max_acceleration: 0 21 | joint3: 22 | has_velocity_limits: true 23 | max_velocity: 1.6199300000000001 24 | has_acceleration_limits: false 25 | max_acceleration: 0 26 | joint4: 27 | has_velocity_limits: true 28 | max_velocity: 1.6199300000000001 29 | has_acceleration_limits: false 30 | max_acceleration: 0 31 | joint5: 32 | has_velocity_limits: true 33 | max_velocity: 1.6199300000000001 34 | has_acceleration_limits: false 35 | max_acceleration: 0 36 | joint6: 37 | has_velocity_limits: true 38 | max_velocity: 1.6199300000000001 39 | has_acceleration_limits: false 40 | max_acceleration: 0 41 | joint7: 42 | has_velocity_limits: true 43 | max_velocity: 1.6199300000000001 44 | has_acceleration_limits: false 45 | max_acceleration: 0 46 | joint8: 47 | has_velocity_limits: true 48 | max_velocity: 1.6199300000000001 49 | has_acceleration_limits: false 50 | max_acceleration: 0 -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | arm: 2 | kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin 3 | kinematics_solver_search_resolution: 0.0050000000000000001 4 | kinematics_solver_timeout: 0.0050000000000000001 -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/config/moveit.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz_common/Displays 3 | Name: Displays 4 | Property Tree Widget: 5 | Expanded: 6 | - /MotionPlanning1 7 | - Class: rviz_common/Help 8 | Name: Help 9 | - Class: rviz_common/Views 10 | Name: Views 11 | Visualization Manager: 12 | Displays: 13 | - Class: rviz_default_plugins/Grid 14 | Name: Grid 15 | Value: true 16 | - Class: moveit_rviz_plugin/MotionPlanning 17 | Name: MotionPlanning 18 | Planned Path: 19 | Loop Animation: true 20 | State Display Time: 0.05 s 21 | Trajectory Topic: display_planned_path 22 | Planning Scene Topic: monitored_planning_scene 23 | Robot Description: robot_description 24 | Scene Geometry: 25 | Scene Alpha: 1 26 | Scene Robot: 27 | Robot Alpha: 0.5 28 | Value: true 29 | Global Options: 30 | Fixed Frame: world 31 | Tools: 32 | - Class: rviz_default_plugins/Interact 33 | - Class: rviz_default_plugins/MoveCamera 34 | - Class: rviz_default_plugins/Select 35 | Value: true 36 | Views: 37 | Current: 38 | Class: rviz_default_plugins/Orbit 39 | Distance: 2.0 40 | Focal Point: 41 | X: -0.1 42 | Y: 0.25 43 | Z: 0.30 44 | Name: Current View 45 | Pitch: 0.5 46 | Target Frame: world 47 | Yaw: -0.623 48 | Window Geometry: 49 | Height: 975 50 | QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 51 | Width: 1200 52 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/config/moveit_controllers.yaml: -------------------------------------------------------------------------------- 1 | # MoveIt uses this configuration for controller management 2 | 3 | moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager 4 | 5 | moveit_simple_controller_manager: 6 | controller_names: 7 | - arm_controller 8 | - gripper_controller 9 | 10 | arm_controller: 11 | type: FollowJointTrajectory 12 | action_ns: follow_joint_trajectory 13 | default: true 14 | joints: 15 | - joint1 16 | - joint2 17 | - joint3 18 | - joint4 19 | - joint5 20 | - joint6 21 | gripper_controller: 22 | type: FollowJointTrajectory 23 | action_ns: follow_joint_trajectory 24 | default: true 25 | joints: 26 | - joint7 27 | - joint8 -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/config/pilz_cartesian_limits.yaml: -------------------------------------------------------------------------------- 1 | # Limits for the Pilz planner 2 | cartesian_limits: 3 | max_trans_vel: 1.0 4 | max_trans_acc: 2.25 5 | max_trans_dec: -5.0 6 | max_rot_vel: 1.57 7 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/config/piper.ros2_control.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | mock_components/GenericSystem 10 | 11 | 12 | 13 | 14 | ${initial_positions['joint1']} 15 | 16 | 17 | 18 | 19 | 20 | 21 | ${initial_positions['joint2']} 22 | 23 | 24 | 25 | 26 | 27 | 28 | ${initial_positions['joint3']} 29 | 30 | 31 | 32 | 33 | 34 | 35 | ${initial_positions['joint4']} 36 | 37 | 38 | 39 | 40 | 41 | 42 | ${initial_positions['joint5']} 43 | 44 | 45 | 46 | 47 | 48 | 49 | ${initial_positions['joint6']} 50 | 51 | 52 | 53 | 54 | 55 | 56 | ${initial_positions['joint7']} 57 | 58 | 59 | 60 | 61 | 62 | 63 | ${initial_positions['joint8']} 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/config/piper.srdf: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/config/piper.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/config/ros2_controllers.yaml: -------------------------------------------------------------------------------- 1 | # This config file is used by ros2_control 2 | controller_manager: 3 | ros__parameters: 4 | update_rate: 100 # Hz 5 | 6 | arm_controller: 7 | type: joint_trajectory_controller/JointTrajectoryController 8 | 9 | 10 | gripper_controller: 11 | type: joint_trajectory_controller/JointTrajectoryController 12 | 13 | 14 | joint_state_broadcaster: 15 | type: joint_state_broadcaster/JointStateBroadcaster 16 | 17 | arm_controller: 18 | ros__parameters: 19 | joints: 20 | - joint1 21 | - joint2 22 | - joint3 23 | - joint4 24 | - joint5 25 | - joint6 26 | command_interfaces: 27 | - position 28 | state_interfaces: 29 | - position 30 | - velocity 31 | gripper_controller: 32 | ros__parameters: 33 | joints: 34 | - joint7 35 | - joint8 36 | command_interfaces: 37 | - position 38 | state_interfaces: 39 | - position 40 | - velocity -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/launch/demo.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_demo_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v5").to_moveit_configs() 7 | return generate_demo_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/launch/move_group.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_move_group_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v5").to_moveit_configs() 7 | return generate_move_group_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/launch/moveit_rviz.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_moveit_rviz_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v5").to_moveit_configs() 7 | return generate_moveit_rviz_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/launch/rsp.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_rsp_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v5").to_moveit_configs() 7 | return generate_rsp_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/launch/setup_assistant.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_setup_assistant_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v5").to_moveit_configs() 7 | return generate_setup_assistant_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/launch/spawn_controllers.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_spawn_controllers_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v5").to_moveit_configs() 7 | return generate_spawn_controllers_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/launch/static_virtual_joint_tfs.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v5").to_moveit_configs() 7 | return generate_static_virtual_joint_tfs_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/launch/warehouse_db.launch.py: -------------------------------------------------------------------------------- 1 | from moveit_configs_utils import MoveItConfigsBuilder 2 | from moveit_configs_utils.launches import generate_warehouse_db_launch 3 | 4 | 5 | def generate_launch_description(): 6 | moveit_config = MoveItConfigsBuilder("piper", package_name="piper_moveit_config_v5").to_moveit_configs() 7 | return generate_warehouse_db_launch(moveit_config) 8 | -------------------------------------------------------------------------------- /piper/piper_moveit_config_v5/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | piper_moveit_config_v5 5 | 0.3.0 6 | 7 | An automatically generated package with all the configuration and launch files for using the piper with the MoveIt Motion Planning Framework 8 | 9 | agilex 10 | 11 | BSD 12 | 13 | http://moveit.ros.org/ 14 | https://github.com/ros-planning/moveit2/issues 15 | https://github.com/ros-planning/moveit2 16 | 17 | agilex 18 | 19 | ament_cmake 20 | 21 | moveit_ros_move_group 22 | moveit_kinematics 23 | moveit_planners 24 | moveit_simple_controller_manager 25 | joint_state_publisher 26 | joint_state_publisher_gui 27 | tf2_ros 28 | xacro 29 | 31 | 32 | 33 | controller_manager 34 | moveit_configs_utils 35 | moveit_ros_move_group 36 | moveit_ros_visualization 37 | moveit_ros_warehouse 38 | moveit_setup_assistant 39 | piper_description 40 | robot_state_publisher 41 | rviz2 42 | rviz_common 43 | rviz_default_plugins 44 | tf2_ros 45 | warehouse_ros_mongo 46 | xacro 47 | 48 | 49 | 50 | ament_cmake 51 | 52 | 53 | --------------------------------------------------------------------------------