Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

upgrade 新探测器驱动 #2

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion include/radiation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,14 +7,18 @@
#include <boost/asio.hpp>
#include <geometry_msgs/PointStamped.h>
#include <std_msgs/Float64.h>

union BytesToFloat {
float f;
unsigned char bytes[4];
};
class radiation
{
private:
ros::NodeHandle nh;
ros::Publisher pub_;
//std_msgs::Float64 final_data;
geometry_msgs::PointStamped final_data;
union BytesToFloat btf;
public:
radiation(){}//构造函数
virtual ~radiation(){}//虚析构函数
Expand Down
39 changes: 24 additions & 15 deletions src/radiation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@ boost::system::error_code err;
/********************************************************
串口发送控制命令
********************************************************/
const unsigned char header[7] = {0x03, 0x31, 0x00, 0x30, 0x04, 0x7B, 0x3F};
const unsigned char header[8] = {0x01, 0x03, 0x00, 0x00, 0x00, 0X02, 0xC4, 0x0B};

bool radiation::radiation_init()//初始化函数
{
//串口参数初始化
sp.set_option(serial_port::baud_rate(9600));
sp.set_option(serial_port::baud_rate(19200));
sp.set_option(serial_port::flow_control(serial_port::flow_control::none));
sp.set_option(serial_port::parity(serial_port::parity::none));
sp.set_option(serial_port::stop_bits(serial_port::stop_bits::one));
Expand All @@ -32,7 +32,7 @@ uint16_t radiation::getCrc16(unsigned char *ptr)
{
uint16_t CRCV = 0xFFFF;
unsigned char iB, i, j;
for(i = 0;i < 9; i++)
for(i = 0;i < 7; i++)
{
CRCV ^= *ptr++;
for(j = 0; j < 8 ;j++)
Expand All @@ -54,10 +54,10 @@ uint16_t radiation::getCrc16(unsigned char *ptr)
********************************************************/
void radiation::writeContral()
{
static unsigned char buf[7] = {0}; //
static unsigned char buf[8] = {0}; //

// 控制消息
for (int i = 0; i < 7; i++)
for (int i = 0; i < 8; i++)
{
buf[i] = header[i];
//ROS_INFO("%02x",buf[i]);
Expand Down Expand Up @@ -86,10 +86,10 @@ bool radiation::readradiation()
try
{
boost::asio::streambuf response;
//ROS_INFO("ready to read");
// ROS_INFO("ready to read");
// boost::asio::read_until(sp, response, "\r\n", err);//\r\n
boost::asio::read( sp, boost::asio::buffer( buf , 11 ) );
ROS_INFO("read successful");
boost::asio::read( sp, boost::asio::buffer( buf , 9 ) );
// ROS_INFO("read successful");

// copy(istream_iterator<unsigned char>(istream(&response) >> noskipws),
// istream_iterator<unsigned char>(),
Expand All @@ -110,28 +110,37 @@ bool radiation::readradiation()
ROS_ERROR("Received message header error!");
return false;
}
//ROS_INFO("CRC校验");
// ROS_INFO("CRC校验");
// 检查信息校验值
check = getCrc16(buf); //getCrc16计算得出
//ROS_INFO("%02X",check);
// ROS_INFO("%02X",check);
low_byte = (check >> 0)& 0x00ff ;
//ROS_INFO("%02X",low_byte);
high_byte = (check >> 8)& 0x00ff ;
//ROS_INFO("%02X",high_byte);
if (low_byte != buf[9] || high_byte != buf[10]) //接受的低字节放在高位,高字节放在底位
if (low_byte != buf[7] || high_byte != buf[8]) //接受的低字节放在高位,高字节放在底位
{
ROS_ERROR("Received data check sum error!");
return false;
}
ROS_INFO("CRC校验成功!");
// ROS_INFO("CRC校验成功!");

//ROS_INFO("开始计算辐射值!");
// 读取辐射值 -----------
receive_data = (buf[5] << 24) + (buf[6] << 16) + (buf[7] << 8) + (buf[8]);
btf.bytes[0] = buf[6]; // 这些值只是示例
btf.bytes[1] = buf[5];
btf.bytes[2] = buf[4];
btf.bytes[3] = buf[3];
// btf.bytes[0] = 0xCD; // 0.20uS/v
// btf.bytes[1] = 0xCC;
// btf.bytes[2] = 0x4C;
// btf.bytes[3] = 0x3E;
// receive_data = (buf[5] << 24) + (buf[6] << 16) + (buf[7] << 8) + (buf[8]);
receive_data = btf.f;
//ROS_INFO("%d",receive_data);
final_data.header.stamp = ros::Time::now();
final_data.point.x = double(receive_data / 100.0);
ROS_INFO("辐射值%f",final_data.point.x);
final_data.point.x = btf.f;
ROS_INFO("辐射值%f",btf.f);

// 辐射数据发布
pub_.publish(final_data);
Expand Down