笔者有一个需求,需要结合ROS做模拟量采集。有一种解决方法是ADC芯片+STM32主控,通过串口的方式与上位机通信,但串口通信速度很慢,达不到要求遂放弃。也考虑过使用NI的数据采集卡,貌似NI没有给ubuntu作配套,也放弃了。在淘宝上找到一款凌智电子的DAQ,价格便宜,也能满足使用需求,故做记录。
系统环境 ubuntu20.04 + ROS noetic
硬件设备 i5-12500+凌智电子DAQ122
驱动要到gitee下载,支持ubuntu x86_64的驱动要注意分支TestZKFT。
git clone --branch=TestZKFT https://gitee.com/Lockzhiner-Electronics/DAQ122-IPC.git
下在之后可以尝试运行 几个demo,都是用Qt写的,也可以拷贝Linux/libdaq的目录单独开发。最关键的是 liblibdaq-2.0.0.so这个文件,下面以ROS为例子怎么调用.so文件。
新建工作空间,功能包等流程不再赘述,网上已经有很多教程了。着重讲cmakelist的配置。
沿用官方demo中QT的使用,因此
find_package(
Qt5 REQUIRED COMPONENTS Core Widgets
)
除此之外,还要包含头文件目录,除了包含官方libdaq的路径以外,还要包含QT安装的路径
include_directories(
include/daq_122 #自己写了一个.h文件
${catkin_INCLUDE_DIRS}
${CMAKE_CURRENT_SOURCE_DIR}/include/daq_122
${CMAKE_CURRENT_SOURCE_DIR}/include/daq_122/include
${CMAKE_CURRENT_SOURCE_DIR}/include/daq_122/third_party/include
${catkin_INCLUDE_DIRS}
${Qt5Core_INCLUDE_DIRS}
${Qt5Widgets_INCLUDE_DIRS}
)
链接官方的.so库文件
link_directories(
lib/x86_64 # 相对路径,指定动态链接库的访问路径
${catkin_LIB_DIRS}
)
再就是ROS 编译C++的cmake写法了。虽然so文件叫liblibdaq-2.0.0,但cmake中需要去掉一个lib才能执行下去。
add_library(${PROJECT_NAME}
src/daq_read.cpp
)
add_executable(daq_read src/daq_read.cpp)
add_dependencies(daq_read ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(daq_read
${catkin_LIBRARIES}
libdaq-2.0.0 #这里额外注意,编译时候cmake会自动加个前缀lib
Qt5::Core
Qt5::Widgets
)
至此,完成了cmakelist的写法。
此外还有package.xml文件,需要引用如下
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>qtbase5-dev</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<build_export_depend>geometry_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>qtbase5-dev</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
其中geometry_msgs是笔者实现自己功能用的一个包,可以不用,其他的包都是必须的。
现在要写一个.h文件,定义一些变量。之前cmake已经有了对QT的引用,因此直接用QT函数就行。
# ifndef DAQ_READ_H
# define DAQ_READ_H
#include <ros/ros.h>
#include <QVector>
#include <QDebug>
#include <geometry_msgs/Vector3.h>
#include <libdaq/device/DAQ122/daq122.h>
using namespace libdaq::device;
DAQ122 daq_device;
uint8_t adc_channel_state_ = 0b11111111;
uint8_t legal_channel_size = 8;
uint32_t storage_depth = 1;
QVector<QVector<double>> receive_data(8);
geometry_msgs::Vector3 laser_distance;
# endif
各个变量的作用,参考官方的示例即可。
接下来是C++文件,运行程序要求有sudo 权限。笔者这里用前三个姿态,以5K频率读,再以5K频率发送,设置如下
#include <ros/ros.h>
#include <geometry_msgs/Vector3.h>
#include "data_read.h"
/*
运行这个程序要求sudo权限
sudo su
然后输入你的用户名+密码
包含两部分 ros+daq读取
*/
void DAQcallback()
{
auto read_result = true;
for (int i = 0; i < 3; i++) {
// 判断当前通道是否打开,没有打开则跳过
if((adc_channel_state_ & (0b00000001) << i) == 0){
continue;
}
// 读取数据
read_result = daq_device.TryReadADCData(i, receive_data[i].data(), receive_data[i].size(), 1000);
if(!read_result){
}
}
QVector<double> x_data(storage_depth);
for (int var = 0; var < storage_depth; ++var) {
x_data[var] = 1000.0 / storage_depth * var;
}
// read_result = daq_device.TryReadADCData(1,receive_data.data(),10,10);
// 只配置了三个通道
auto current_buffer_size = daq_device.GetADCBufferDataSize(0);
qDebug() << receive_data[1];
// 停止读取
// daq_device.StopADCCollection();
// receive_data[0].clear();
// receive_data[1].clear();
// receive_data[2].clear();
laser_distance.x = receive_data[0].at(0);
laser_distance.y = receive_data[1].at(0);
laser_distance.z = receive_data[2].at(0);
}
int main(int argc, char *argv[])
{
// 初始化DAQ122
if (!daq_device.InitializeDevice())
{
std::cout << "InitializeDevice Error";
}
if(!daq_device.ConnectedDevice())
{
std::cout << "ConnectedDevice Error";
}
// 采样范围5V
auto voltage_range = DAQVoltage::Voltage5V;
// 采样频率定义为1KHz
auto sample_rate = DAQADCSampleRate::SampleRate5K;
if (!daq_device.ConfigureADCParameters(sample_rate, voltage_range))
{
std::cout << "Configure Error";
}
// 配置前三个通道为输入
adc_channel_state_ = DAQADCChannel::AIN1 | DAQADCChannel::AIN2 | DAQADCChannel::AIN3;
daq_device.ConfigADCChannel(adc_channel_state_);
// 开始采集数据
daq_device.StartADCCollection();
// 定义存储数组
for (int var = 0; var < receive_data.size(); ++var) {
receive_data[var].resize(storage_depth);
}
// ros初始化
ros::init(argc,argv,"daq_pub_node");
ros::NodeHandle nh;
// 1ms 执行一次
ros::Publisher daq_pub = nh.advertise<geometry_msgs::Vector3>("daq_pub",10);
ros::Duration(1).sleep();
// 判断当前数据是否已经满足读取的条件
if(!daq_device.ADCDataIsReady(storage_depth)){
std::cout << "not enough" << std::endl;
}
auto read_result = true;
for (int i = 0; i < legal_channel_size; i++) {
// 判断当前通道是否打开,没有打开则跳过
if((adc_channel_state_ & (0b00000001) << i) == 0){
continue;
}
// 读取数据
read_result = daq_device.TryReadADCData(i, receive_data[i].data(), receive_data[i].size(), 1000);
if(!read_result){
// qDebug() << "Error";
}
}
QVector<double> x_data(storage_depth);
for (int var = 0; var < storage_depth; ++var) {
x_data[var] = 1000.0 / storage_depth * var;
}
ros::Rate daq_rate(5000);
while (ros::ok())
{
DAQcallback();
daq_pub.publish(laser_distance);
daq_rate.sleep();
}
// ros::spin();
return 0;
}
编译,运行即可将数据发送到rostopic中。
采集正弦信号
采集方波信号
采集三角波信号
更多回帖