1、build.sh。2、uss

This commit is contained in:
lyq 2026-04-09 11:14:29 +08:00
parent ca36d8289d
commit 2d4f07d069
3 changed files with 43 additions and 8 deletions

22
build.sh Executable file
View File

@ -0,0 +1,22 @@
#!/bin/bash
set -e
if [ $# -eq 0 ]; then
echo "编译全部"
colcon build \
--symlink-install \
--cmake-args -DCMAKE_BUILD_TYPE=Release
else
echo "编译: $@"
colcon build \
--symlink-install \
--cmake-args -DCMAKE_BUILD_TYPE=Release \
--packages-up-to "$@"
fi
source install/setup.bash
echo "编译完成"

View File

@ -4,7 +4,7 @@
// 超声波传感器的CAN ID定义 (J1939格式: 0x18EC5700)
// Priority: 0x18, PGN: 0xEC00 (60416), Device ID: 0x57 (87)
constexpr uint32_t USS_CAN_ID = 0x18EC5700;
constexpr uint32_t USS_CAN_ID = 0x18EC0057;
constexpr uint32_t USS_CAN_MASK = 0xFFFFFFFF; // 精确匹配
UssDriver::UssDriver() : print_debug_(false), initialized_(false)
@ -41,8 +41,8 @@ bool UssDriver::init(const std::string& can_interface)
// 设置CAN过滤器只接收超声波的CAN数据
struct can_filter filter;
filter.can_id = USS_CAN_ID;
filter.can_mask = USS_CAN_MASK;
filter.can_id = USS_CAN_ID | CAN_EFF_FLAG;
filter.can_mask = CAN_EFF_MASK | CAN_EFF_FLAG;
std::vector<struct can_filter> filters;
filters.push_back(filter);

View File

@ -67,21 +67,34 @@ class UssNode : public rclcpp::Node
message.data[0] = static_cast<int8_t>(uss_data.distances_calib[0]);
message.data[1] = static_cast<int8_t>(uss_data.distances_calib[1]);
message.data[2] = static_cast<int8_t>(uss_data.distances_calib[2]);
message.data[3] = static_cast<int8_t>(uss_data.distances_calib[3]);
message.data[4] = static_cast<int8_t>(uss_data.distances_calib[4]);
message.data[5] = static_cast<int8_t>(uss_data.distances_calib[5]);
message.data[6] = static_cast<int8_t>(uss_data.distances_calib[6]);
message.data[7] = static_cast<int8_t>(uss_data.distances_calib[7]);
message.data[7] = static_cast<int8_t>(uss_data.distances_calib[2]);
// 发布消息
uss_publisher_->publish(message);
// 调试打印
for (int i = 0; i < 8; i++)
{
RCLCPP_INFO(this->get_logger(), "USS %d: %d cm", i + 1, static_cast<int>(message.data[i]));
}
RCLCPP_INFO(
this->get_logger(),
"USS 1~4: %d %d %d %d cm",
static_cast<int8_t>(uss_data.distances_calib[0]),
static_cast<int8_t>(uss_data.distances_calib[1]),
static_cast<int8_t>(uss_data.distances_calib[2]),
static_cast<int8_t>(uss_data.distances_calib[3]));
RCLCPP_INFO(
this->get_logger(),
"USS 5~8: %d %d %d %d cm",
static_cast<int8_t>(uss_data.distances_calib[4]),
static_cast<int8_t>(uss_data.distances_calib[5]),
static_cast<int8_t>(uss_data.distances_calib[6]),
static_cast<int8_t>(uss_data.distances_calib[7]));
RCLCPP_INFO(this->get_logger(), "==========================");
}
else
{