diff --git a/src/rm_decision/src/decision_node.cpp b/src/rm_decision/src/decision_node.cpp index d42b600..f6a3ffe 100644 --- a/src/rm_decision/src/decision_node.cpp +++ b/src/rm_decision/src/decision_node.cpp @@ -25,7 +25,7 @@ DecisionNode::DecisionNode(const rclcpp::NodeOptions &options) std::bind(&DecisionNode::data_ref_callback, this, std::placeholders::_1)); data_aim_sub_ = this->create_subscription( - "/vision/aim", 10, + "/data_aim", 10, std::bind(&DecisionNode::data_aim_callback, this, std::placeholders::_1)); nav_status_sub_ = this->create_subscription( diff --git a/src/rm_nav/README.md b/src/rm_nav/README.md index 36e7848..f87c99c 100644 --- a/src/rm_nav/README.md +++ b/src/rm_nav/README.md @@ -6,9 +6,9 @@ RoboMaster比赛 纯mid360激光雷达导航项目 -ros2 launch rm_nav_bringup bringup_sim.launch.py \ - world:=RMUL2026 \ - mode:=mapping \ +ros2 launch rm_nav_bringup bringup_real.launch.py \ + world:=RUML \ + mode:=nav \ lio:=fastlio \ lio_rviz:=True \ nav_rviz:=True diff --git a/src/rm_nav/rm_nav_bringup/config/reality/MID360_config.json b/src/rm_nav/rm_nav_bringup/config/reality/MID360_config.json index 0d214e6..e6c180b 100644 --- a/src/rm_nav/rm_nav_bringup/config/reality/MID360_config.json +++ b/src/rm_nav/rm_nav_bringup/config/reality/MID360_config.json @@ -25,11 +25,11 @@ }, "lidar_configs" : [ { - "ip" : "192.168.1.119", + "ip" : "192.168.1.190", "pcl_data_type" : 1, "pattern_mode" : 0, "extrinsic_parameter" : { - "roll": 0.0, + "roll": 180.0, "pitch": 0.0, "yaw": 0.0, "x": 0, diff --git a/src/rm_nav/rm_nav_bringup/config/reality/segmentation_real.yaml b/src/rm_nav/rm_nav_bringup/config/reality/segmentation_real.yaml index ee8a194..e4f2784 100644 --- a/src/rm_nav/rm_nav_bringup/config/reality/segmentation_real.yaml +++ b/src/rm_nav/rm_nav_bringup/config/reality/segmentation_real.yaml @@ -7,7 +7,7 @@ ground_segmentation: n_bins: 120 # number of radial bins. n_segments: 360 # number of radial segments. - max_dist_to_line: 0.1 # maximum vertical distance of point to line to be considered ground. + max_dist_to_line: 0.06 # maximum vertical distance of point to line to be considered ground. sensor_height: 0.59 # REAL sensor height above ground. min_slope: -0.4 # minimum slope of a ground line. diff --git a/src/rm_nav/rm_nav_bringup/launch/bringup_real.launch.py b/src/rm_nav/rm_nav_bringup/launch/bringup_real.launch.py index 9ee5314..1d803e3 100644 --- a/src/rm_nav/rm_nav_bringup/launch/bringup_real.launch.py +++ b/src/rm_nav/rm_nav_bringup/launch/bringup_real.launch.py @@ -337,16 +337,6 @@ def generate_launch_description(): ] ) - bringup_fake_vel_transform_node = Node( - package='fake_vel_transform', - executable='fake_vel_transform_node', - output='screen', - parameters=[{ - 'use_sim_time': use_sim_time, - 'spin_speed': 0.0 # rad/s - }] - ) - start_mapping = Node( condition = LaunchConfigurationEquals('mode', 'mapping'), package='slam_toolbox', @@ -385,7 +375,6 @@ def generate_launch_description(): ld.add_action(bringup_pointcloud_to_laserscan_node) ld.add_action(bringup_LIO_group) ld.add_action(start_localization_group) - ld.add_action(bringup_fake_vel_transform_node) ld.add_action(start_mapping) ld.add_action(start_navigation2) diff --git a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/visualization.h b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/visualization.h index c46dbe8..6a520c6 100644 --- a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/visualization.h +++ b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/include/teb_local_planner/visualization.h @@ -86,7 +86,7 @@ public: * @param nh local rclcpp::Node::SharedPtr * @param cfg const reference to the TebConfig class for parameters */ - TebVisualization(const rclcpp_lifecycle::LifecycleNode::SharedPtr & nh, const TebConfig& cfg); + TebVisualization(const nav2_util::LifecycleNode::SharedPtr & nh, const TebConfig& cfg); /** @name Publish to topics */ //@{ diff --git a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/teb_local_planner_ros.cpp b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/teb_local_planner_ros.cpp index 6060d8b..5374a92 100644 --- a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/teb_local_planner_ros.cpp +++ b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/teb_local_planner_ros.cpp @@ -198,7 +198,11 @@ void TebLocalPlannerROS::configure( std::shared_ptr costmap_ros) { nh_ = parent; - auto node = nh_.lock(); + auto node = std::dynamic_pointer_cast(nh_.lock()); + if (!node) { + throw nav2_core::ControllerException( + "Failed to cast controller parent node to nav2_util::LifecycleNode"); + } logger_ = node->get_logger(); clock_ = node->get_clock(); diff --git a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/visualization.cpp b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/visualization.cpp index 025960d..393dce7 100644 --- a/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/visualization.cpp +++ b/src/rm_nav/rm_navigation/teb_local_planner/teb_local_planner/src/visualization.cpp @@ -61,7 +61,7 @@ void publishPlan(const std::vector& path, pub->publish(gui_path); } -TebVisualization::TebVisualization(const rclcpp_lifecycle::LifecycleNode::SharedPtr & nh, const TebConfig& cfg) : nh_(nh), cfg_(&cfg), initialized_(false) +TebVisualization::TebVisualization(const nav2_util::LifecycleNode::SharedPtr & nh, const TebConfig& cfg) : nh_(nh), cfg_(&cfg), initialized_(false) { } diff --git a/src/rm_serial_driver/src/rm_serial_driver.cpp b/src/rm_serial_driver/src/rm_serial_driver.cpp index dfe4364..e56e7c3 100644 --- a/src/rm_serial_driver/src/rm_serial_driver.cpp +++ b/src/rm_serial_driver/src/rm_serial_driver.cpp @@ -41,7 +41,7 @@ namespace rm_serial_driver // 订阅视觉控制指令 data_ai_sub_ = this->create_subscription( - "/gimbal/vision", 10, + "/data_ai", 10, std::bind(&RMSerialDriver::data_ai_callback, this, std::placeholders::_1)); // 同时订阅导航控制指令(用于底盘控制) @@ -52,7 +52,7 @@ namespace rm_serial_driver RCLCPP_INFO(get_logger(), "话题配置:"); RCLCPP_INFO(get_logger(), " 发布: /data_mcu (MCU状态)"); RCLCPP_INFO(get_logger(), " 发布: /data_ref (裁判系统)"); - RCLCPP_INFO(get_logger(), " 订阅: /gimbal/vision (视觉控制)"); + RCLCPP_INFO(get_logger(), " 订阅: /data_aim (视觉控制)"); RCLCPP_INFO(get_logger(), " 订阅: /cmd_vel_move (导航控制)"); // 打开串口