Compare commits

...

13 Commits

8 changed files with 295 additions and 188 deletions

View File

@ -5,6 +5,8 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
link_directories(${CMAKE_CURRENT_SOURCE_DIR}/lib)
# Find dependencies
find_package(sweeper_interfaces REQUIRED)
find_package(ament_cmake REQUIRED)
@ -19,6 +21,8 @@ add_executable(mc_node ${SRC_FILES})
ament_target_dependencies(mc_node rclcpp std_msgs sweeper_interfaces)
target_link_libraries(mc_node controlcan pthread)
# Set include directories for the target
target_include_directories(
mc_node
@ -31,6 +35,15 @@ target_compile_features(mc_node PUBLIC c_std_99 cxx_std_17)
install(TARGETS mc_node DESTINATION lib/${PROJECT_NAME})
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
set(LIB_DIR ${CMAKE_CURRENT_SOURCE_DIR}/lib)
# libcontrolcan.so
install(
FILES
${LIB_DIR}/libcontrolcan.so
DESTINATION lib
)
# Handle testing if needed
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)

View File

@ -42,25 +42,13 @@ public:
// 设置接收回调
void setReceiveCallback(ReceiveCallback callback, void *userData = nullptr);
// 设置硬件过滤规则
bool setFilter(const std::vector<can_filter> &filters);
// 追加一个过滤器
bool addFilter(const can_filter &filter);
// 追加一组过滤器
bool addFilters(const std::vector<can_filter> &filters);
private:
void receiveThreadFunc();
bool applyFilters(); // 应用当前filters_
int sockfd = -1;
std::atomic<bool> running{false};
std::thread receiveThread;
ReceiveCallback callback;
void *userData = nullptr;
std::vector<can_filter> filters_; // 当前所有过滤器
};
#endif // CAN_DRIVER_H

104
src/mc/include/mc/controlcan.h Executable file
View File

@ -0,0 +1,104 @@
#ifndef CONTROLCAN_H
#define CONTROLCAN_H
////文件版本v2.02 20190609
//接口卡类型定义
#define VCI_USBCAN1 3
#define VCI_USBCAN2 4
#define VCI_USBCAN2A 4
#define VCI_USBCAN_E_U 20
#define VCI_USBCAN_2E_U 21
//函数调用返回状态值
#define STATUS_OK 1
#define STATUS_ERR 0
#define USHORT unsigned short int
#define BYTE unsigned char
#define CHAR char
#define UCHAR unsigned char
#define UINT unsigned int
#define DWORD unsigned int
#define PVOID void*
#define ULONG unsigned int
#define INT int
#define UINT32 UINT
#define LPVOID void*
#define BOOL BYTE
#define TRUE 1
#define FALSE 0
//1.ZLGCAN系列接口卡信息的数据类型。
typedef struct _VCI_BOARD_INFO{
USHORT hw_Version;
USHORT fw_Version;
USHORT dr_Version;
USHORT in_Version;
USHORT irq_Num;
BYTE can_Num;
CHAR str_Serial_Num[20];
CHAR str_hw_Type[40];
USHORT Reserved[4];
} VCI_BOARD_INFO,*PVCI_BOARD_INFO;
//2.定义CAN信息帧的数据类型。
typedef struct _VCI_CAN_OBJ{
UINT ID;
UINT TimeStamp;
BYTE TimeFlag;
BYTE SendType;
BYTE RemoteFlag;//是否是远程帧
BYTE ExternFlag;//是否是扩展帧
BYTE DataLen;
BYTE Data[8];
BYTE Reserved[3];
}VCI_CAN_OBJ,*PVCI_CAN_OBJ;
//3.定义初始化CAN的数据类型
typedef struct _INIT_CONFIG{
DWORD AccCode;
DWORD AccMask;
DWORD Reserved;
UCHAR Filter;
UCHAR Timing0;
UCHAR Timing1;
UCHAR Mode;
}VCI_INIT_CONFIG,*PVCI_INIT_CONFIG;
///////// new add struct for filter /////////
typedef struct _VCI_FILTER_RECORD{
DWORD ExtFrame; //是否为扩展帧
DWORD Start;
DWORD End;
}VCI_FILTER_RECORD,*PVCI_FILTER_RECORD;
#ifdef __cplusplus
#define EXTERN_C extern "C"
#else
#define EXTERN_C
#endif
EXTERN_C DWORD VCI_OpenDevice(DWORD DeviceType,DWORD DeviceInd,DWORD Reserved);
EXTERN_C DWORD VCI_CloseDevice(DWORD DeviceType,DWORD DeviceInd);
EXTERN_C DWORD VCI_InitCAN(DWORD DeviceType, DWORD DeviceInd, DWORD CANInd, PVCI_INIT_CONFIG pInitConfig);
EXTERN_C DWORD VCI_ReadBoardInfo(DWORD DeviceType,DWORD DeviceInd,PVCI_BOARD_INFO pInfo);
EXTERN_C DWORD VCI_SetReference(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,DWORD RefType,PVOID pData);
EXTERN_C ULONG VCI_GetReceiveNum(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
EXTERN_C DWORD VCI_ClearBuffer(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
EXTERN_C DWORD VCI_StartCAN(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
EXTERN_C DWORD VCI_ResetCAN(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
EXTERN_C ULONG VCI_Transmit(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_CAN_OBJ pSend,UINT Len);
EXTERN_C ULONG VCI_Receive(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_CAN_OBJ pReceive,UINT Len,INT WaitTime);
EXTERN_C DWORD VCI_UsbDeviceReset(DWORD DevType,DWORD DevIndex,DWORD Reserved);
EXTERN_C DWORD VCI_FindUsbDevice2(PVCI_BOARD_INFO pInfo);
#endif

BIN
src/mc/lib/libcontrolcan.a Executable file

Binary file not shown.

BIN
src/mc/lib/libcontrolcan.so Executable file

Binary file not shown.

View File

@ -1,59 +1,73 @@
#include "mc/can_driver.h"
#include "mc/controlcan.h"
#include <cstring>
#include <stdexcept>
#include <iostream>
#include <thread>
#include <fcntl.h>
#include <unistd.h>
#include <sys/ioctl.h>
#include <net/if.h>
#include <iostream>
#include <linux/can.h>
#include <linux/can/raw.h>
#include <net/if.h>
#include <stdexcept>
#include <sys/ioctl.h>
#include <thread>
#include <unistd.h>
#include <mutex>
std::mutex canMutex;
DWORD deviceType = VCI_USBCAN2; // 或 VCI_USBCAN_2E_U 等
DWORD deviceIndex = 0; // 通常为 0第一个设备
DWORD channelIndex = 0; // 通道号0 表示 CAN11 表示 CAN2
CANDriver::CANDriver() = default;
CANDriver::~CANDriver()
{
close();
}
CANDriver::~CANDriver() { close(); }
bool CANDriver::open(const std::string &interface)
{
if (running)
return false;
sockfd = socket(PF_CAN, SOCK_RAW, CAN_RAW);
if (sockfd < 0)
// 参数可解析 interface 设定 channelIndex例如 interface="can0" =>
// channelIndex=0
deviceType = VCI_USBCAN2;
deviceIndex = 0;
channelIndex = (interface == "can1") ? 1 : 0;
if (VCI_OpenDevice(deviceType, deviceIndex, 0) != STATUS_OK)
{
perror("socket");
std::cerr << "VCI_OpenDevice failed" << std::endl;
return false;
}
struct ifreq ifr;
std::strncpy(ifr.ifr_name, interface.c_str(), IFNAMSIZ - 1);
ifr.ifr_name[IFNAMSIZ - 1] = '\0';
VCI_INIT_CONFIG config{};
config.AccCode = 0;
config.AccMask = 0xFFFFFFFF;
config.Filter = 0; // 接收所有
config.Timing0 = 0x00; // 500Kbps 示例(需查文档确认 Timing
config.Timing1 = 0x1C;
config.Mode = 0; // 正常模式
if (ioctl(sockfd, SIOCGIFINDEX, &ifr) < 0)
if (VCI_InitCAN(deviceType, deviceIndex, channelIndex, &config) !=
STATUS_OK)
{
perror("ioctl");
::close(sockfd);
std::cerr << "VCI_InitCAN failed" << std::endl;
VCI_CloseDevice(deviceType, deviceIndex);
return false;
}
struct sockaddr_can addr{};
addr.can_family = AF_CAN;
addr.can_ifindex = ifr.ifr_ifindex;
if (bind(sockfd, reinterpret_cast<struct sockaddr *>(&addr), sizeof(addr)) < 0)
if (VCI_StartCAN(deviceType, deviceIndex, channelIndex) != STATUS_OK)
{
perror("bind");
::close(sockfd);
std::cerr << "VCI_StartCAN failed" << std::endl;
VCI_CloseDevice(deviceType, deviceIndex);
return false;
}
// 设置为非阻塞
int flags = fcntl(sockfd, F_GETFL, 0);
fcntl(sockfd, F_SETFL, flags | O_NONBLOCK);
if (VCI_ClearBuffer(deviceType, deviceIndex, channelIndex) != 1)
{
std::cerr << "VCI_ClearBuffer failed" << std::endl;
VCI_CloseDevice(deviceType, deviceIndex);
return false;
}
running = true;
receiveThread = std::thread(&CANDriver::receiveThreadFunc, this);
@ -69,11 +83,11 @@ void CANDriver::close()
if (receiveThread.joinable())
receiveThread.join();
if (sockfd >= 0)
{
::close(sockfd);
sockfd = -1;
}
// 先清空缓冲区,防止缓冲区残留数据导致重复接收
VCI_ClearBuffer(deviceType, deviceIndex, channelIndex);
VCI_ResetCAN(deviceType, deviceIndex, channelIndex);
VCI_CloseDevice(deviceType, deviceIndex);
}
bool CANDriver::sendFrame(const CANFrame &frame)
@ -81,18 +95,18 @@ bool CANDriver::sendFrame(const CANFrame &frame)
if (!running)
return false;
struct can_frame raw_frame{};
raw_frame.can_id = frame.id;
if (frame.ext)
raw_frame.can_id |= CAN_EFF_FLAG;
if (frame.rtr)
raw_frame.can_id |= CAN_RTR_FLAG;
raw_frame.can_dlc = frame.dlc;
std::memcpy(raw_frame.data, frame.data, frame.dlc);
VCI_CAN_OBJ obj{};
obj.ID = frame.id;
obj.RemoteFlag = frame.rtr ? 1 : 0;
obj.ExternFlag = frame.ext ? 1 : 0;
obj.SendType = 0; // 普通发送
obj.DataLen = frame.dlc;
std::memcpy(obj.Data, frame.data, frame.dlc);
if (write(sockfd, &raw_frame, sizeof(raw_frame)) != sizeof(raw_frame))
std::lock_guard<std::mutex> lock(canMutex); // 加锁
if (VCI_Transmit(deviceType, deviceIndex, channelIndex, &obj, 1) != 1)
{
perror("write");
std::cerr << "VCI_Transmit failed" << std::endl;
return false;
}
@ -105,69 +119,40 @@ void CANDriver::setReceiveCallback(ReceiveCallback callback, void *userData)
this->userData = userData;
}
bool CANDriver::setFilter(const std::vector<can_filter> &filters)
{
if (!running)
return false;
filters_ = filters;
return applyFilters();
}
bool CANDriver::addFilter(const can_filter &filter)
{
filters_.push_back(filter);
return applyFilters();
}
bool CANDriver::addFilters(const std::vector<can_filter> &filters)
{
filters_.insert(filters_.end(), filters.begin(), filters.end());
return applyFilters();
}
bool CANDriver::applyFilters()
{
if (!running)
return false;
if (filters_.empty())
{
setsockopt(sockfd, SOL_CAN_RAW, CAN_RAW_FILTER, nullptr, 0);
return true;
}
if (setsockopt(sockfd, SOL_CAN_RAW, CAN_RAW_FILTER,
filters_.data(), filters_.size() * sizeof(can_filter)) < 0)
{
perror("setsockopt");
return false;
}
return true;
}
void CANDriver::receiveThreadFunc()
{
struct can_frame raw_frame;
constexpr int maxFrames = 2500;
VCI_CAN_OBJ rec[maxFrames];
while (running)
{
ssize_t nbytes = read(sockfd, &raw_frame, sizeof(raw_frame));
if (nbytes < 0)
ULONG len = 0;
{
if (errno != EAGAIN)
perror("read");
std::lock_guard<std::mutex> lock(canMutex); // 加锁
len = VCI_Receive(deviceType, deviceIndex, channelIndex, rec, maxFrames, 10);
}
if (len == 0)
{
std::this_thread::sleep_for(std::chrono::milliseconds(10));
continue;
}
if (nbytes == sizeof(raw_frame) && callback)
for (ULONG i = 0; i < len && callback; ++i)
{
CANFrame frame;
frame.id = raw_frame.can_id & CAN_EFF_MASK;
frame.ext = static_cast<bool>(raw_frame.can_id & CAN_EFF_FLAG);
frame.rtr = static_cast<bool>(raw_frame.can_id & CAN_RTR_FLAG);
frame.dlc = raw_frame.can_dlc;
std::memcpy(frame.data, raw_frame.data, raw_frame.can_dlc);
frame.id = rec[i].ID;
frame.ext = rec[i].ExternFlag != 0;
frame.rtr = rec[i].RemoteFlag != 0;
frame.dlc = rec[i].DataLen;
if (frame.dlc > 8)
{
std::cerr << "Invalid CAN data length: " << (int)frame.dlc << std::endl;
frame.dlc = 8; // 或跳过此帧
}
std::memcpy(frame.data, rec[i].Data, frame.dlc);
callback(frame, userData);
}
}

View File

@ -1,12 +1,12 @@
#include <cstdio>
#include <iostream>
#include <iomanip>
#include "mc/can_driver.h"
#include "mc/can_struct.h"
#include "mc/get_config.h"
#include "rclcpp/rclcpp.hpp"
#include "sweeper_interfaces/msg/can_frame.hpp"
#include "sweeper_interfaces/msg/mc_ctrl.hpp"
#include <cstdio>
#include <iomanip>
#include <iostream>
namespace sweeperMsg = sweeper_interfaces::msg;
@ -23,7 +23,7 @@ std::atomic<bool> vcu_awake = false; // 是否唤醒成功
rclcpp::Time last_vcu_msg_time; // 上次收到vcu数据帧的时间
// 全局开关,控制是否打印 CAN 消息到终端
bool g_can_print_enable = false;
bool g_can_print_enable = true;
struct ControlCache
{
@ -47,7 +47,8 @@ struct ControlCache
return false;
auto now = std::chrono::steady_clock::now();
auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(now - last_update_time);
auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(
now - last_update_time);
if (duration.count() > 100) // ms超时
{
@ -95,23 +96,27 @@ void receiveHandler(const CANFrame &frame, void *userData)
auto msg = sweeperMsg::CanFrame();
msg.id = frame.id;
msg.dlc = frame.dlc;
msg.data.assign(frame.data, frame.data + frame.dlc);
size_t len = frame.dlc <= 8 ? frame.dlc : 8;
msg.data.assign(frame.data, frame.data + len);
publisher->publish(msg);
// 根据开关决定是否打印 CAN 消息
if (g_can_print_enable)
if (g_can_print_enable && len > 0)
{
std::stringstream ss;
ss << "CAN ID: ";
if (frame.id > 0x7FF)
ss << std::hex << std::uppercase << frame.id;
else
ss << std::hex << std::uppercase << std::setw(5) << std::setfill(' ') << frame.id;
ss << std::hex << std::uppercase << std::setw(5) << std::setfill(' ')
<< frame.id;
ss << " Data: ";
for (int i = 0; i < frame.dlc; ++i)
{
ss << std::setw(2) << std::setfill('0') << std::hex << (int)frame.data[i] << " ";
ss << std::setw(2) << std::setfill('0') << std::hex << (int)frame.data[i]
<< " ";
}
RCLCPP_INFO(node->get_logger(), "%s", ss.str().c_str());
@ -162,32 +167,33 @@ void VCUWakeUp()
void setupTimers(rclcpp::Node::SharedPtr node)
{
// VCU 唤醒帧发送定时器1Hz
static rclcpp::TimerBase::SharedPtr timer_wakeup = node->create_wall_timer(
std::chrono::seconds(1), [node]()
static rclcpp::TimerBase::SharedPtr timer_wakeup =
node->create_wall_timer(std::chrono::seconds(1), [node]()
{
if (!vcu_awake.load())
{
RCLCPP_INFO(node->get_logger(), "[TIMER][VCU] Not awake, sending wake-up frame...");
if (!vcu_awake.load()) {
RCLCPP_INFO(node->get_logger(),
"[TIMER][VCU] Not awake, sending wake-up frame...");
VCUWakeUp();
} });
// vcu报文 watchdog 检查200ms
static rclcpp::TimerBase::SharedPtr timer_estop_watchdog = node->create_wall_timer(
std::chrono::milliseconds(200), [node]()
static rclcpp::TimerBase::SharedPtr timer_estop_watchdog =
node->create_wall_timer(std::chrono::milliseconds(200), [node]()
{
auto now = node->now();
auto elapsed = now - last_vcu_msg_time;
if (vcu_msg_received.load() && elapsed > rclcpp::Duration::from_seconds(0.5))
{
RCLCPP_WARN(node->get_logger(), "[TIMER][VCU] message timeout, resetting wake-up state.");
if (vcu_msg_received.load() &&
elapsed > rclcpp::Duration::from_seconds(0.5)) {
RCLCPP_WARN(node->get_logger(),
"[TIMER][VCU] message timeout, resetting wake-up state.");
vcu_msg_received.store(false);
vcu_awake.store(false);
} });
// MCU控制50Hz
static rclcpp::TimerBase::SharedPtr timer_mcu = node->create_wall_timer(
std::chrono::milliseconds(20), []()
static rclcpp::TimerBase::SharedPtr timer_mcu =
node->create_wall_timer(std::chrono::milliseconds(20), []()
{
sweeperMsg::McCtrl msg = get_safe_control();
@ -199,8 +205,8 @@ void setupTimers(rclcpp::Node::SharedPtr node)
canctl.sendFrame(mcu_cmd.toFrame()); });
// EPS 控制20Hz
static rclcpp::TimerBase::SharedPtr timer_eps = node->create_wall_timer(
std::chrono::milliseconds(50), []()
static rclcpp::TimerBase::SharedPtr timer_eps =
node->create_wall_timer(std::chrono::milliseconds(50), []()
{
sweeperMsg::McCtrl msg = get_safe_control();
@ -212,8 +218,8 @@ void setupTimers(rclcpp::Node::SharedPtr node)
canctl.sendFrame(eps_cmd.toFrame()); });
// VCU 控制10Hz
static rclcpp::TimerBase::SharedPtr timer_vcu = node->create_wall_timer(
std::chrono::milliseconds(100), []()
static rclcpp::TimerBase::SharedPtr timer_vcu =
node->create_wall_timer(std::chrono::milliseconds(100), []()
{
sweeperMsg::McCtrl msg = get_safe_control();
@ -229,9 +235,8 @@ void setupTimers(rclcpp::Node::SharedPtr node)
vcu2_cmd.setSpray(msg.spray);
vcu2_cmd.setSweeepCtrl(msg.sweep_ctrl);
// canctl.sendFrame(vcu1_cmd.toFrame());
// canctl.sendFrame(vcu2_cmd.toFrame());
});
canctl.sendFrame(vcu1_cmd.toFrame());
canctl.sendFrame(vcu2_cmd.toFrame()); });
}
int main(int argc, char **argv)
@ -244,7 +249,8 @@ int main(int argc, char **argv)
RCLCPP_INFO(node->get_logger(), "Starting mc package...");
// 创建一个 Publisher
auto can_publisher = node->create_publisher<sweeperMsg::CanFrame>("can_data", 10);
auto can_publisher =
node->create_publisher<sweeperMsg::CanFrame>("can_data", 10);
// 创建 Subscriber收控制指令
auto subscriber = node->create_subscription<sweeperMsg::McCtrl>(
@ -260,7 +266,8 @@ int main(int argc, char **argv)
if (!canctl.open(mc_config.can_dev))
{
RCLCPP_ERROR(node->get_logger(), "Failed to open CAN interface: %s", mc_config.can_dev.c_str());
RCLCPP_ERROR(node->get_logger(), "Failed to open CAN interface: %s",
mc_config.can_dev.c_str());
return -1;
}

View File

@ -8,7 +8,8 @@
namespace sweeperMsg = sweeper_interfaces::msg;
constexpr float EPS_GEAR_RATIO = 16.5f;
constexpr float DEG_PER_SEC_TO_RPM = 1.0f / 6.0f;
constexpr float GEAR_RATIO = 7.0f;
constexpr float DELTA_T = 0.02f; // 20ms
const uint16_t speed[3] = {192, 992, 1792};
@ -90,7 +91,15 @@ private:
{
msg.gear = 1; // R挡
}
else
{
msg.gear = 0;
msg.brake = 1;
msg.rpm = 0;
}
if (ch_data[7] != 992)
{
// 油门 / 刹车逻辑
if (ch_data[1] <= speed[1])
{
@ -102,6 +111,7 @@ private:
msg.brake = 0;
msg.rpm = static_cast<uint8_t>(MCU_RPM_MAX * (ch_data[1] - speed[1]) / (speed[2] - speed[1]));
}
}
// 一键清扫
if (ch_data[5] == 1792)
@ -122,13 +132,13 @@ private:
}
// 转向逻辑
float target_angle = (992 - static_cast<float>(ch_data[3])) / 800 * EPS_ANGLE_MAX;
float target_angle = (static_cast<float>(ch_data[3] - 992)) / 800 * EPS_ANGLE_MAX;
// 角速度(度/秒)
float angle_speed = fabs(target_angle - current_feedback_angle) / DELTA_T;
// 电机转速单位rpm
float motor_rpm = angle_speed * EPS_GEAR_RATIO;
float motor_rpm = angle_speed * DEG_PER_SEC_TO_RPM * GEAR_RATIO;
// 限制电机转速到 [120, 1500] 范围,防止过小/过大
uint16_t can_speed = std::clamp(