Compare commits

..

No commits in common. "37554e7dd7efb8e75943de478e8dcde78dd0da29" and "07f61ea89ec3107a4f87e5698e4c3d474c92dfc0" have entirely different histories.

12 changed files with 29 additions and 25 deletions

View File

@ -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<rm_msgs::msg::DataAim>(
"/data_aim", 10,
"/vision/aim", 10,
std::bind(&DecisionNode::data_aim_callback, this, std::placeholders::_1));
nav_status_sub_ = this->create_subscription<rm_msgs::msg::NavStatus>(

View File

@ -6,9 +6,9 @@ RoboMaster比赛
纯mid360激光雷达导航项目
ros2 launch rm_nav_bringup bringup_real.launch.py \
world:=RUML \
mode:=nav \
ros2 launch rm_nav_bringup bringup_sim.launch.py \
world:=RMUL2026 \
mode:=mapping \
lio:=fastlio \
lio_rviz:=True \
nav_rviz:=True

View File

@ -25,11 +25,11 @@
},
"lidar_configs" : [
{
"ip" : "192.168.1.190",
"ip" : "192.168.1.119",
"pcl_data_type" : 1,
"pattern_mode" : 0,
"extrinsic_parameter" : {
"roll": 180.0,
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0,
"x": 0,

View File

@ -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.06 # maximum vertical distance of point to line to be considered ground.
max_dist_to_line: 0.1 # 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.

View File

@ -337,6 +337,16 @@ 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',
@ -375,6 +385,7 @@ 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)

View File

@ -54,7 +54,6 @@
#include <std_msgs/msg/color_rgba.hpp>
#include <rclcpp/rclcpp.hpp>
#include <nav2_util/lifecycle_node.hpp>
#include "teb_local_planner/planner_interface.h"
#include "teb_local_planner/teb_config.h"

View File

@ -41,7 +41,6 @@
#include <math.h>
#include <nav2_util/lifecycle_node.hpp>
// teb stuff
#include "teb_local_planner/teb_config.h"
@ -711,7 +710,6 @@ protected:
RotType prefer_rotdir_; //!< Store whether to prefer a specific initial rotation in optimization (might be activated in case the robot oscillates)
// internal objects (memory management owned)
nav2_util::LifecycleNode::SharedPtr node_; //!< ROS2 lifecycle node pointer
TebVisualizationPtr visualization_; //!< Instance of the visualization class
TimedElasticBand teb_; //!< Actual trajectory object
RobotFootprintModelPtr robot_model_; //!< Robot model

View File

@ -86,7 +86,7 @@ public:
* @param nh local rclcpp::Node::SharedPtr
* @param cfg const reference to the TebConfig class for parameters
*/
TebVisualization(const nav2_util::LifecycleNode::SharedPtr & nh, const TebConfig& cfg);
TebVisualization(const rclcpp_lifecycle::LifecycleNode::SharedPtr & nh, const TebConfig& cfg);
/** @name Publish to topics */
//@{

View File

@ -198,11 +198,7 @@ void TebLocalPlannerROS::configure(
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) {
nh_ = parent;
auto node = std::dynamic_pointer_cast<nav2_util::LifecycleNode>(nh_.lock());
if (!node) {
throw nav2_core::PlannerException(
"Failed to cast controller parent node to nav2_util::LifecycleNode");
}
auto node = nh_.lock();
logger_ = node->get_logger();
clock_ = node->get_clock();

View File

@ -61,7 +61,7 @@ void publishPlan(const std::vector<geometry_msgs::msg::PoseStamped>& path,
pub->publish(gui_path);
}
TebVisualization::TebVisualization(const nav2_util::LifecycleNode::SharedPtr & nh, const TebConfig& cfg) : nh_(nh), cfg_(&cfg), initialized_(false)
TebVisualization::TebVisualization(const rclcpp_lifecycle::LifecycleNode::SharedPtr & nh, const TebConfig& cfg) : nh_(nh), cfg_(&cfg), initialized_(false)
{
}

View File

@ -41,7 +41,7 @@ namespace rm_serial_driver
// 订阅视觉控制指令
data_ai_sub_ = this->create_subscription<rm_msgs::msg::DataAI>(
"/data_ai", 10,
"/gimbal/vision", 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(), " 订阅: /data_aim (视觉控制)");
RCLCPP_INFO(get_logger(), " 订阅: /gimbal/vision (视觉控制)");
RCLCPP_INFO(get_logger(), " 订阅: /cmd_vel_move (导航控制)");
// 打开串口