浏览代码

[fix]足式里程计中加入姿态信息。

rundong 9 月之前
父节点
当前提交
5186fdde6b
共有 2 个文件被更改,包括 11 次插入11 次删除
  1. 8 8
      saturn_controller/launch/saturn_ros2.launch.py
  2. 3 3
      saturn_controller/src/config_handler.cpp

+ 8 - 8
saturn_controller/launch/saturn_ros2.launch.py

@@ -4,11 +4,12 @@ import launch
 import launch_ros.actions
 
 def generate_launch_description():
-    config = os.path.join(                                                     
-             get_package_share_directory('saturn_controller'),                    
-             'config',                                                          
-             'config.yaml'                                                      
-    )
+
+    robot_name = os.getenv('ROBOT_NAME', 'default_robot')
+    robot_type = os.getenv('ROBOT_TYPE', 'default_type')
+
+    print("Robot name: " + robot_name)
+    print("Robot type: " + robot_type)
 
     component_manager_node = launch_ros.actions.Node(
         package='rclcpp_components',
@@ -23,9 +24,8 @@ def generate_launch_description():
             launch_ros.descriptions.ComposableNode(
                 package='saturn_controller',
                 plugin='saturn_ros2::SaturnController',
-                namespace = "GS_003",
-                name='saturn_controller',
-                parameters=[config]
+                namespace = robot_name,
+                name='saturn_controller'
             ),
         ]
     )

+ 3 - 3
saturn_controller/src/config_handler.cpp

@@ -15,8 +15,8 @@ void ConfigHandler::loadConfig() {
     // 声明参数                                                                
     motion_computer_ip_address_ = node_->declare_parameter("motion_computer_ip_address", "127.0.0.1");
                                                                                
-    main_timer_frequency_ = node_->declare_parameter("main_timer_frequency", 1.0);                                                      
-    imu_timer_frequency_ = node_->declare_parameter("imu_timer_frequency", 1.0);                                                     
-    legged_odom_timer_frequency_ = node_->declare_parameter("legged_odom_timer_frequency", 1.0);
+    main_timer_frequency_ = node_->declare_parameter("main_timer_frequency", 50.0);                                                      
+    imu_timer_frequency_ = node_->declare_parameter("imu_timer_frequency", 300.0);                                                     
+    legged_odom_timer_frequency_ = node_->declare_parameter("legged_odom_timer_frequency", 100.0);
 }
 }