- 前面两部分已经利用SocketCAN类和协议解析文件实现了CAN口数据的获取、存储和解析工作。虽然已经进行了数据解析工作,但是我们并没有进行解析后结果发布的工作,因此这部分将会利用ROS结点及msg消息和srv服务来对解析后的结果进行发布。同协议组织部分类似,这部分也会将之前数据接收和处理封装为一个ROS结点来管理,同时对于各部分协议也会创建单独的话题来对解析结果进行发布。
文章目录
1、radar_cfg_ros 部分
-
利用ROS中的srv服务对RadarCfg进行配置。
-
srv(服务):一个srv文件描述一个服务。它由两部分组成:请求(request)和响应(response)。这两部分用一条
---
线分开,srv文件具体描述的就是一个服务中请求和响应分别要求的消息格式。 -
服务是两个节点之间的通信,是点对点的,一个节点发送消息,还需要等待接受节点的响应。
-
首先创建雷达配置时要发送的自定义的请求类型:MaxDistance.srv,OutputType.srv,RadarPower.srv,RCSThreshold.srv,SensorID.srv,SortIndex.srv。
-
MaxDistance.srv
# Maximum distance of far scan (near scan maximum
# distance is set proportionally to half of the far scan).
# The maximum distance will also change the range
# resolution proportionally. For example, 200 m
# maximum distance will lead to:
# - far scan 200 m with 1.79 m range resolution,
# - near scan 100 m with 0.42 m range resolution.
# Standard Range: 196 – 260 m
# Extended Range: 196 – 1200 m
uint8 max_distance
---
- OutputType.srv
# none
# send objects
# send clusters
uint8 output_type
---
- RadarPower.srv
# Configures the transmitted radar power (Tx
# attenuation). The output RCS of cluster and objects
# will be compensated for this attenuation. Reducing
# the output power can improve detection in case of
# close range scenarios or inside rooms.
#
# Standard
# -3dB Tx gain
# -6dB Tx gain
# -9dB Tx gain
uint8 radar_power
---
- RCSThreshold.srv
# Sets the sensitivity of the cluster detection to standard
# (0x0) or high sensitivity (0x1)
uint8 rcs_threshold
---
- SensorID.srv
# Sensor ID 0 – 7
uint8 sensor_id
---
- SortIndex.srv
# Selects the sorting index for the object list (ignored for
# clusters as they are always sorted by range)
#
# no sorting
# sorted by range
# sorted by RCS
uint8 sort_index
---
-
配置CmakeLists.txt文件
find_package(std_srvs REQUIRED) add_service_files( FILES MaxDistance.srv OutputType.srv RadarPower.srv RCSThreshold.srv SensorID.srv SortIndex.srv )
-
radar_cfg_ros.hpp:定义用于发送雷达配置请求的RadarCfgROS类
#ifndef ARS_40X_RADAR_CFG_ROS_HPP
#define ARS_40X_RADAR_CFG_ROS_HPP
#include <ros/ros.h>
#include <std_srvs/SetBool.h>
#include <cstdint>
#include "ars_40X/ars_40X_can.hpp" //定义的协议解析接口文件
#include "ars_40X/MaxDistance.h"
#include "ars_40X/OutputType.h"
#include "ars_40X/RadarPower.h"
#include "ars_40X/RCSThreshold.h"
#include "ars_40X/SensorID.h"
#include "ars_40X/SortIndex.h" //定义的6种服务请求
namespace ars_40X {
class RadarCfgROS {
public:
RadarCfgROS(ros::NodeHandle &nh, ARS_40X_CAN *ars_40X_can);
~RadarCfgROS();
bool set_max_distance( //service回调函数声明,输入参数req,输出参数res(这里主要是用于发送请求,配置成功后不需要接收响应返回值)
MaxDistance::Request &req,
MaxDistance::Response & /*res*/); //MaxDistance为服务类型
bool set_sensor_id(
SensorID::Request &req,
SensorID::Response & /*res*/);
bool set_radar_power(
RadarPower::Request &req,
RadarPower::Response & /*res*/);
bool set_output_type(
OutputType::Request &req,
OutputType::Response & /*res*/);
bool set_send_quality(
std_srvs::SetBool::Request &req,
std_srvs::SetBool::Response & /*res*/);
bool set_send_ext_info(
std_srvs::SetBool::Request &req,
std_srvs::SetBool::Response & /*res*/);
bool set_sort_index(
SortIndex::Request &req,
SortIndex::Response & /*res*/);
bool set_ctrl_relay_cfg(
std_srvs::SetBool::Request &req,
std_srvs::SetBool::Response & /*res*/);
bool set_store_in_nvm(
std_srvs::SetBool::Request &req,
std_srvs::SetBool::Response & /*res*/);
bool set_rcs_threshold(
RCSThreshold::Request &req,
RCSThreshold::Response & /*res*/);
private:
ARS_40X_CAN *ars_40X_can_; //定义协议接口类的指针
radar_cfg::RadarCfg *radar_cfg_; //定义雷达配置协议类的指针
ros::ServiceServer set_max_distance_service_;
ros::ServiceServer set_sensor_id_service_;
ros::ServiceServer set_radar_power_service_;
ros::ServiceServer set_output_type_service_;
ros::ServiceServer set_send_quality_service_;
ros::ServiceServer set_send_ext_info_service_;
ros::ServiceServer set_sort_index_service_;
ros::ServiceServer set_ctrl_relay_cfg_service_;
ros::ServiceServer set_store_in_nvm_service_;
ros::ServiceServer set_rcs_threshold_service_; //创建Server对象
};
}
#endif //ARS_40X_RADAR_CFG_ROS_HPP
- RadarCfgROS类的实现
#include "ars_40X/ros/radar_cfg_ros.hpp"
namespace ars_40X {
RadarCfgROS::RadarCfgROS(ros::NodeHandle &nh, ARS_40X_CAN *ars_40X_can) :
ars_40X_can_(ars_40X_can) { //参数列表协议接口类的初始化,以及获取节点句柄
radar_cfg_ = ars_40X_can->get_radar_cfg(); //获取RadarCfg类对象
set_max_distance_service_ =
nh.advertiseService("set_max_distance", &RadarCfgROS::set_max_distance, this); //创建名为set_max_distance的server,注册回调函数set_max_distance()
set_sensor_id_service_ = nh.advertiseService("set_sensor_id", &RadarCfgROS::set_sensor_id, this); //创建名为set_sensor_id的server,注册回调函数set_sensor_id()
set_radar_power_service_ =
nh.advertiseService("set_radar_power", &RadarCfgROS::set_radar_power, this); //创建名为set_radar_power的server,注册回调函数set_radar_power()
set_output_type_service_ =
nh.advertiseService("set_output_type", &RadarCfgROS::set_output_type, this); //创建名为set_output_type的server,注册回调函数set_output_type()
set_send_quality_service_ =
nh.advertiseService("set_send_quality", &RadarCfgROS::set_send_quality, this); //创建名为set_send_quality的server,注册回调函数set_send_quality()
set_send_ext_info_service_ =
nh.advertiseService("set_send_ext_info", &RadarCfgROS::set_send_ext_info, this); //创建名为set_send_ext_info的server,注册回调函数set_send_ext_info()
set_sort_index_service_ =
nh.advertiseService("set_sort_index", &RadarCfgROS::set_sort_index, this); //创建名为set_sort_index的server,注册回调函数set_sort_index()
set_ctrl_relay_cfg_service_ =
nh.advertiseService("set_ctrl_relay_cfg", &RadarCfgROS::set_ctrl_relay_cfg, this); //创建名为set_ctrl_relay_cfg的server,注册回调函数set_ctrl_relay_cfg()
set_store_in_nvm_service_ =
nh.advertiseService("set_store_in_nvm", &RadarCfgROS::set_store_in_nvm, this); //创建名为set_store_in_nvm的server,注册回调函数set_store_in_nvm()
set_rcs_threshold_service_ =
nh.advertiseService("set_rcs_threshold", &RadarCfgROS::set_rcs_threshold, this); //创建名为set_rcs_threshold的server,注册回调函数set_rcs_threshold()
}
RadarCfgROS::~RadarCfgROS() {
}
bool RadarCfgROS::set_max_distance(
MaxDistance::Request &req,
MaxDistance::Response & /*res*/) {
if (!radar_cfg_->set_max_distance(static_cast<uint64_t>(req.max_distance))) {
return false;
}
ars_40X_can_->send_radar_data(can_messages::RadarCfg);
return true;
} //回调函数的实现
bool RadarCfgROS::set_sensor_id(
SensorID::Request &req,
SensorID::Response & /*res*/) {
if (!radar_cfg_->set_sensor_id(req.sensor_id)) {
return false;
}
ars_40X_can_->send_radar_data(can_messages::RadarCfg);
return true;
}
bool RadarCfgROS::set_radar_power(
RadarPower::Request &req,
RadarPower::Response & /*res*/) {
if (!radar_cfg_->set_radar_power(req.radar_power)) {
return false;
}
ars_40X_can_->send_radar_data(can_messages::RadarCfg);
return true;
}
bool RadarCfgROS::set_output_type(
OutputType::Request &req,
OutputType::Response & /*res*/) {
if (!radar_cfg_->set_output_type(req.output_type)) {
return false;
}
ars_40X_can_->send_radar_data(can_messages::RadarCfg);
return true;
}
bool RadarCfgROS::set_send_quality(
std_srvs::SetBool::Request &req,
std_srvs::SetBool::Response & /*res*/) {
radar_cfg_->set_send_quality(static_cast<bool>(req.data));
ars_40X_can_->send_radar_data(can_messages::RadarCfg);
return true;
}
bool RadarCfgROS::set_send_ext_info(
std_srvs::SetBool::Request &req,
std_srvs::SetBool::Response & /*res*/) {
radar_cfg_->set_send_ext_info(static_cast<bool>(req.data));
ars_40X_can_->send_radar_data(can_messages::RadarCfg);
return true;
}
bool RadarCfgROS::set_sort_index(
SortIndex::Request &req,
SortIndex::Response & /*res*/) {
if (!radar_cfg_->set_sort_index(req.sort_index)) {
return false;
}
ars_40X_can_->send_radar_data(can_messages::RadarCfg);
return true;
}
bool RadarCfgROS::set_ctrl_relay_cfg(
std_srvs::SetBool::Request &req,
std_srvs::SetBool::Response & /*res*/) {
radar_cfg_->set_ctrl_relay_cfg(static_cast<bool>(req.data));
ars_40X_can_->send_radar_data(can_messages::RadarCfg);
return true;
}
bool RadarCfgROS::set_store_in_nvm(
std_srvs::SetBool::Request &req,
std_srvs::SetBool::Response & /*res*/) {
radar_cfg_->set_store_in_nvm(static_cast<bool>(req.data));
ars_40X_can_->send_radar_data(can_messages::RadarCfg);
return true;
}
bool RadarCfgROS::set_rcs_threshold(
RCSThreshold::Request &req,
RCSThreshold::Response & /*res*/) {
if (!radar_cfg_->set_rcs_threshold(req.rcs_threshold)) {
return false;
}
ars_40X_can_->send_radar_data(can_messages::RadarCfg);
return true;
}
}
2、radar_state_ros部分
-
利用ROS中的msg进行RadarState信息输出。
-
msg(消息):msg文件就是文本文件,用于描述ROS消息的字段。它们用于为不同编程语言编写的消息生成源代码。msg文件就是简单的文本文件,每行都有一个字段类型和字段名称。
-
定义用于RadarState信息输出的msg: RadarStatus.msg
bool read_status //读取配置参数的结果状态
bool write_status //配置参数保存到 NVM 中的结果状态
int16 max_distance //当前far scan最大距离的配置参数
bool persistent_error //检测到复位后可能不会消失的内部错误
bool interference //检测到与另一个雷达传感器的干扰
bool temperature_error //如果温度低于或高于定义的范围,错误将激活。离开后会自动退出
bool temporary_error //检测到传感器复位后最有可能消失的临时错误
bool voltage_error //如果工作电压低于或高于规定范围5秒以上,则错误将激活
int8 sensor_id //当前传感器ID (0-7)
int8 sort_index //当前目标列表的排序方式0x0: no sorting 0x1: sorted by range 0x2: sorted by RCS
int8 radar_power_cfg //当前雷达发射功率的参数配置0x0: Standard 0x1: -3dB Tx gain 0x2: -6dB Tx gain 0x3: -9dB Tx gain
bool ctrl_relay_cfg //0x0: inactive 0x1: active
int8 output_type_cfg //当前输出模式为Clusters 或者Objects
bool send_quality_cfg //0x0: inactive 0x1: active
bool send_ext_info_cfg //0x0: inactive 0x1: active
int8 motion_rx_state //显示速度和角速度输入信号的状态,0x0: input ok 0x1: speed missing 0x2: yaw rate missing 0x3: speed and yaw rate missing
bool rcs_threshold //0x0 Standard 0x1 High sensitivity
- 创建RadarStateROS节点,用于解析后雷达状态信息的发布
#ifndef ARS_40X_RADAR_STATE_ROS_HPP
#define ARS_40X_RADAR_STATE_ROS_HPP
#include <ros/ros.h>
#include <std_srvs/SetBool.h>
#include <cstdint>
#include "ars_40X/ars_40X_can.hpp"
#include "ars_40X/RadarStatus.h"
namespace ars_40X {
class RadarStateROS {
public:
RadarStateROS(ros::NodeHandle &nh, ARS_40X_CAN *ars_40X_can); //有参构造函数,用于获取节点句柄以及协议接口类对象
~RadarStateROS();
void send_radar_state();
private:
ros::Publisher radar_state_pub_; //创建Publisher对象
ARS_40X_CAN *ars_40X_can_;
radar_state::RadarState *radar_state_;
};
}
#endif //ARS_40X_RADAR_STATE_ROS_HPP
- RadarStateROS类的实现
#include "ars_40X/ros/radar_state_ros.hpp"
namespace ars_40X {
RadarStateROS::RadarStateROS(ros::NodeHandle &nh, ARS_40X_CAN *ars_40X_can) :
ars_40X_can_(ars_40X_can) {
radar_state_ = ars_40X_can->get_radar_state(); //获取RadarState类对象
radar_state_pub_ = nh.advertise<RadarStatus>("radar_status", 1); //发布名为radar_status的topic,消息类型为自定义的类型RadarStatus,发布序列的大小为1。
}
RadarStateROS::~RadarStateROS() {
}
void RadarStateROS::send_radar_state() {
RadarStatus radar_status_msg; //定义RadarStatus类型的消息
radar_status_msg.read_status = radar_state_->get_read_status();
radar_status_msg.write_status = radar_state_->get_write_status();
radar_status_msg.max_distance = radar_state_->get_max_distance();
radar_status_msg.persistent_error = radar_state_->get_persistent_error_status();
radar_status_msg.interference = radar_state_->get_interference_status();
radar_status_msg.temperature_error = radar_state_->get_temperature_error_status();
radar_status_msg.temporary_error = radar_state_->get_temporary_error_status();
radar_status_msg.voltage_error = radar_state_->get_voltage_error_status();
radar_status_msg.sensor_id = radar_state_->get_sensor_id();
radar_status_msg.sort_index = radar_state_->get_sort_index();
radar_status_msg.radar_power_cfg = radar_state_->get_radar_power_cfg();
radar_status_msg.ctrl_relay_cfg = radar_state_->get_ctrl_relay_cfg();
radar_status_msg.output_type_cfg = radar_state_->get_output_type_cfg();
radar_status_msg.send_quality_cfg = radar_state_->get_send_quality_cfg();
radar_status_msg.send_ext_info_cfg = radar_state_->get_ext_info_cfg();
radar_status_msg.motion_rx_state = radar_state_->get_motion_rx_state();
radar_status_msg.rcs_threshold = radar_state_->get_rcs_threshold(); //对RadarStatus类型消息进行赋值
radar_state_pub_.publish(radar_status_msg); //发布消息
}
}
3、motion_input_signals_ros部分
- 利用MotionInputSignalsROS类来获取/设置运动输入信息
#ifndef ARS_40X_MOTION_INPUT_SIGNALS_ROS_HPP
#define ARS_40X_MOTION_INPUT_SIGNALS_ROS_HPP
#include <ros/ros.h>
#include <nav_msgs/Odometry.h>
#include <cstdint>
#include "ars_40X/ars_40X_can.hpp"
namespace ars_40X {
class MotionInputSignalsROS {
public:
MotionInputSignalsROS(ros::NodeHandle &nh, ARS_40X_CAN *ars_40X_can);
~MotionInputSignalsROS();
private:
void odom_callback(nav_msgs::Odometry msg);
ARS_40X_CAN *ars_40X_can_;
motion_input_signals::SpeedInformation *speed_information_;
motion_input_signals::YawRateInformation *yaw_rate_information_;
ros::Subscriber odom_sub_;
};
}
#endif //ARS_40X_MOTION_INPUT_SIGNALS_ROS_HPP
- MotionInputSignalsROS类的实现
#include <ars_40X/ros/motion_input_signals_ros.hpp>
namespace ars_40X {
MotionInputSignalsROS::MotionInputSignalsROS(ros::NodeHandle &nh, ARS_40X_CAN *ars_40X_can) :
ars_40X_can_(ars_40X_can) {
speed_information_ = ars_40X_can_->get_speed_information(); //获取SpeedInformation类对象
yaw_rate_information_ = ars_40X_can_->get_yaw_rate_information(); //获取YawRateInformation类对象
odom_sub_ = nh.subscribe("odom", 10, &MotionInputSignalsROS::odom_callback, this);
} //订阅odom话题,并将获取的数据交由回调函数odom_callback处理
MotionInputSignalsROS::~MotionInputSignalsROS() {
}
void MotionInputSignalsROS::odom_callback(nav_msgs::Odometry msg) {
double speed = msg.twist.twist.linear.x; //从获取的Odometry类型的消息中取出x向的speed信息,(之前协议部分提到 y 默认为0)
speed_information_->set_speed(std::abs(speed)); //利用得到的速度信息对motion输入信息进行设置
if (speed < 0.0) {
speed_information_->set_speed_direction(motion_input_signals::BACKWARD); //speed<0,则速度方向为后向
} else if (speed > 0.0) {
speed_information_->set_speed_direction(motion_input_signals::FORWARD); //speed>0,则速度方向为前向
} else {
speed_information_->set_speed_direction(motion_input_signals::STANDSTILL); //否则,为静止状态
}
ars_40X_can_->send_radar_data(can_messages::SpeedInformation);
yaw_rate_information_->set_yaw_rate(msg.twist.twist.angular.z * 180.0 / M_PI); //获取角速度信息,并将单位从角度改换为弧度
ars_40X_can_->send_radar_data(can_messages::YawRateInformation);
} //运动信息设置
}
4、cluster_list_ros部分
-
利用自定义的消息类型Cluster.msg、ClusterList.msg和ClusterListROS类完成clusters模式下数据解析结果的发布。
-
定义Cluster.msg
uint8 id
geometry_msgs/PoseWithCovariance position
geometry_msgs/TwistWithCovariance relative_velocity
float32 rcs
int8 dynamic_property
int8 class_type
int8 prob_of_exist
int8 ambig_state
int8 invalid_state
- 定义ClusterList.msg
std_msgs/Header header
ars_40X/Cluster[] clusters
- 定义ClusterListROS类
#ifndef ARS_40X_CLUSTER_LIST_ROS_HPP
#define ARS_40X_CLUSTER_LIST_ROS_HPP
#include <ros/ros.h>
#include <cstdint>
#include "ars_40X/ClusterList.h" //引入自定义消息ClusterList生成的头文件
#include "ars_40X/ars_40X_can.hpp" //引入协议接口类
namespace ars_40X {
class ClusterListROS {
public:
ClusterListROS(
ros::NodeHandle &nh, ARS_40X_CAN *ars_40X_can); //有参构造,获取节点句柄以及接口类对象
~ClusterListROS();
void set_frame_id(std::string frame_id);
void send_cluster_0_status();
void send_cluster_1_general();
void send_cluster_2_quality(); //接口类中调用的clusters数据解析结果的发布函数
private:
std::string frame_id_;
ros::Publisher clusters_data_pub_; //创建Publisher发布对象
ClusterList cluster_list; //创建要发布的消息对象
cluster_list::Cluster_0_Status *cluster_0_status_;
cluster_list::Cluster_1_General *cluster_1_general_;
cluster_list::Cluster_2_Quality *cluster_2_quality_; //用于接收clusters数据各部分的接口类对象指针
ARS_40X_CAN *ars_40X_can_; //用于协议接口类对象的指针
int cluster_id_; //用于记录每帧数据中的cluster ID
};
}
#endif //ARS_40X_CLUSTER_LIST_ROS_HPP
- ClusterListROS类的实现
#include "ars_40X/ros/cluster_list_ros.hpp"
namespace ars_40X {
ClusterListROS::ClusterListROS(ros::NodeHandle &nh, ARS_40X_CAN *ars_40X_can) :
ars_40X_can_(ars_40X_can), cluster_id_(0) { //协议接口类以及cluster_id的初始化
cluster_0_status_ = ars_40X_can->get_cluster_0_status();
cluster_1_general_ = ars_40X_can->get_cluster_1_general();
cluster_2_quality_ = ars_40X_can->get_cluster_2_quality(); //利用初始化后的协议接口类对clusters数据内的类对象初始化
clusters_data_pub_ = nh.advertise<ars_40X::ClusterList>("ars_40X/clusters", 10);
} //发布名为ars_40X/clusters的topic,消息类型为自定义的类型ars_40X::ClusterList,发布序列的大小为10。
ClusterListROS::~ClusterListROS() {
}
void ClusterListROS::set_frame_id(std::string frame_id) {
frame_id_ = std::move(frame_id); //设置消息发布时的frame_id
}
void ClusterListROS::send_cluster_0_status() {
cluster_list.header.stamp = ros::Time::now(); //获取系统时间作为header的时间戳
cluster_list.header.frame_id = frame_id_; //数据的frame_id作为header的frame_id
clusters_data_pub_.publish(cluster_list); //发布消息
cluster_id_ = 0; //当前帧的cluster_id置为 0
cluster_list.clusters.clear(); //清空clusters中的内容
}
void ClusterListROS::send_cluster_1_general() {
Cluster cluster; //创建单个cluster对象
cluster.id = cluster_1_general_->get_cluster_id();
cluster.position.pose.position.x = cluster_1_general_->get_cluster_long_dist();
cluster.position.pose.position.y = cluster_1_general_->get_cluster_lat_dist();
cluster.relative_velocity.twist.linear.x = cluster_1_general_->get_cluster_long_rel_vel();
cluster.relative_velocity.twist.linear.y = cluster_1_general_->get_cluster_lat_rel_vel();
cluster.dynamic_property = cluster_1_general_->get_cluster_dyn_prop();
cluster.rcs = cluster_1_general_->get_cluster_rcs(); //利用接收到的cluster_1_general_对象对cluster进行赋值
cluster_list.clusters.push_back(cluster); //将赋值后的cluster对象添加到要发布的消息列表中
}
void ClusterListROS::send_cluster_2_quality() {
cluster_list.clusters[cluster_id_].position.covariance[0] =
pow(cluster_2_quality_->get_cluster_long_dist_rms(), 2); //获取x方向坐标标准差 单位:m
cluster_list.clusters[cluster_id_].position.covariance[7] =
pow(cluster_2_quality_->get_cluster_lat_dist_rms(), 2); //获取y方向坐标标准差 单位:m
cluster_list.clusters[cluster_id_].relative_velocity.covariance[0] =
pow(cluster_2_quality_->get_cluster_long_rel_vel_rms(), 2); //获取x方向相对速度标准差 单位:m/s
cluster_list.clusters[cluster_id_].relative_velocity.covariance[7] =
pow(cluster_2_quality_->get_cluster_lat_rel_vel_rms(), 2); //获取y方向相对速度标准差 单位:m/s
cluster_list.clusters[cluster_id_].prob_of_exist = cluster_2_quality_->get_cluster_pdh0();
cluster_list.clusters[cluster_id_].ambig_state =
cluster_2_quality_->get_cluster_ambiguity_state();
cluster_list.clusters[cluster_id_].invalid_state =
cluster_2_quality_->get_cluster_validity_state(); //利用接收到的cluster_2_quality_对象对相应编号的cluster进行赋值
++cluster_id_; //cluster对应编号+1
}
}
5、object_list_ros部分
-
利用自定义的消息类型Object.msg、ObjectList.msg和ObjectListROS类完成objects模式下数据解析结果的发布。
-
Object.msg
uint8 id
geometry_msgs/PoseWithCovariance position
geometry_msgs/TwistWithCovariance relative_velocity
geometry_msgs/AccelWithCovariance relative_acceleration
float32 length
float32 width
float32 orientation_angle
float32 rcs
int8 dynamic_property
int8 class_type
int8 meas_state
int8 prob_of_exist
- ObjectList.msg
std_msgs/Header header
ars_40X/Object[] objects
- 定义ObjectListROS类
#ifndef ARS_40X_OBJECT_LIST_ROS_HPP
#define ARS_40X_OBJECT_LIST_ROS_HPP
#include <ros/ros.h>
#include <cstdint>
#include "ars_40X/ObjectList.h" //引入自定义消息ObjectList生成的头文件
#include "ars_40X/ars_40X_can.hpp" //引入协议接口类
namespace ars_40X {
class ObjectListROS {
public:
ObjectListROS(ros::NodeHandle &nh, ARS_40X_CAN *ars_40X_can); //有参构造,获取节点句柄以及接口类对象
~ObjectListROS();
void set_frame_id(std::string frame_id);
void send_object_0_status();
void send_object_1_general();
void send_object_2_quality();
void send_object_3_extended(); //接口类中调用的objects数据解析结果的发布函数
private:
std::string frame_id_;
ros::Publisher objects_data_pub_; //创建Publisher发布对象
ARS_40X_CAN *ars_40X_can_;
ObjectList object_list; //创建要发送的消息对象
object_list::Object_0_Status *object_0_status_;
object_list::Object_1_General *object_1_general_;
object_list::Object_2_Quality *object_2_quality_;
object_list::Object_3_Extended *object_3_extended_; //用于接收object数据各部分的接口类对象
int object_2_quality_id_;
int object_3_extended_id_;
};
}
#endif //ARS_40X_OBJECT_LIST_ROS_HPP
- ObjectListROS类的实现
#include "ars_40X/ros/object_list_ros.hpp"
#include <geometry_msgs/Quaternion.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
namespace ars_40X {
ObjectListROS::ObjectListROS(ros::NodeHandle &nh, ARS_40X_CAN *ars_40X_can) :
ars_40X_can_(ars_40X_can) {
object_0_status_ = ars_40X_can_->get_object_0_status();
object_1_general_ = ars_40X_can_->get_object_1_general();
object_2_quality_ = ars_40X_can_->get_object_2_quality();
object_3_extended_ = ars_40X_can_->get_object_3_extended(); //利用获取的协议接口类对象对object数据各部分对象初始化
objects_data_pub_ = nh.advertise<ars_40X::ObjectList>("ars_40X/objects", 10);
} //发布名为ars_40X/objects的topic,消息类型为自定义的类型ars_40X::ObjectList,发布序列的大小为10。
ObjectListROS::~ObjectListROS() {
}
void ObjectListROS::set_frame_id(std::string frame_id) {
frame_id_ = frame_id;
}
void ObjectListROS::send_object_0_status() {
object_list.header.stamp = ros::Time::now(); //获取系统时间作为header的时间戳
object_list.header.frame_id = frame_id_; //数据的frame_id作为header的frame_id
object_list.objects.erase(
object_list.objects.begin() + std::min(object_2_quality_id_, object_3_extended_id_),
object_list.objects.begin() + object_list.objects.size()); //删除object_list中quality_id和extended_id未对齐部分的数据,以最小id为基准。只保留id已经对齐的object的数据,确保object数据的完整性
objects_data_pub_.publish(object_list); //发布object数据
object_list.objects.clear(); //清空objects
object_2_quality_id_ = 0;
object_3_extended_id_ = 0; //数据发布之后quality_id和extended_id重新置0
}
void ObjectListROS::send_object_1_general() {
Object object; //创建单个object对象
object.id = object_1_general_->get_object_id();
object.position.pose.position.x = object_1_general_->get_object_long_dist();
object.position.pose.position.y = object_1_general_->get_object_lat_dist();
object.relative_velocity.twist.linear.x = object_1_general_->get_object_long_rel_vel();
object.relative_velocity.twist.linear.y = object_1_general_->get_object_lat_rel_vel();
object.dynamic_property = object_1_general_->get_object_dyn_prop();
object.rcs = object_1_general_->get_object_rcs(); //利用接收到的object_1_general_对象对object进行赋值
object_list.objects.push_back(object); //将赋值后的object对象添加到要发布的消息列表中
}
void ObjectListROS::send_object_2_quality() {
object_list.objects[object_2_quality_id_].position.covariance[0] =
pow(object_2_quality_->get_object_lat_dist_rms(), 2); //获取x方向坐标标准差 单位:m
object_list.objects[object_2_quality_id_].position.covariance[7] =
pow(object_2_quality_->get_object_long_dist_rms(), 2); //获取y方向坐标标准差 单位:m
object_list.objects[object_2_quality_id_].position.covariance[35] =
pow(object_2_quality_->get_object_orientation_rms(), 2); //获取方位角标准差 单位:deg
object_list.objects[object_2_quality_id_].relative_velocity.covariance[0] =
pow(object_2_quality_->get_object_long_rel_vel_rms(), 2); //获取 x 方向的相对速度的标准差 单位:m/s
object_list.objects[object_2_quality_id_].relative_velocity.covariance[7] =
pow(object_2_quality_->get_object_lat_rel_vel_rms(), 2); //获取 xy 方向的相对速度的标准差 单位:m/s
object_list.objects[object_2_quality_id_].relative_acceleration.covariance[0] =
pow(object_2_quality_->get_object_long_rel_accel_rms(), 2); //获取 x 方向的相对加速度的标准差 单位:m/s2
object_list.objects[object_2_quality_id_].relative_acceleration.covariance[7] =
pow(object_2_quality_->get_object_lat_rel_accel_rms(), 2); //获取 x 方向的相对加速度的标准差 单位:m/s2
object_list.objects[object_2_quality_id_].meas_state = object_2_quality_->get_object_meas_state(); //测量状态:在新的测量周期内 object 是否有效,是否被 clusters 确认。0x0:deleted 0x1:new 0x2:measured 0x3: predicted 0x4:deleted for merge 0x5:new from merge
object_list.objects[object_2_quality_id_].prob_of_exist =
object_2_quality_->get_object_prob_of_exist(); //存在的概率。0x0:invalid 0x1:<25% 0x2:<50% 0x3:<75% 0x4:<90% 0x5:<99% 0x6:<99.9% 0x7:<=100%
++object_2_quality_id_; //object_2_quality_id +1
}
void ObjectListROS::send_object_3_extended() {
object_list.objects[object_3_extended_id_].length = object_3_extended_->get_object_length(); //获取被跟踪object的长度 单位:m
object_list.objects[object_3_extended_id_].width = object_3_extended_->get_object_width(); //获取被跟踪object的宽度 单位:m
tf2::Quaternion q; //定义四元数对象
q.setRPY(0, 0, object_3_extended_->get_object_orientation_angle() * M_PI / 180.0); //弧度化角度,并将 RPY角 转换为 四元数
object_list.objects[object_3_extended_id_].position.pose.orientation.w = q.getW();
object_list.objects[object_3_extended_id_].position.pose.orientation.x = q.getX();
object_list.objects[object_3_extended_id_].position.pose.orientation.y = q.getY();
object_list.objects[object_3_extended_id_].position.pose.orientation.z = q.getZ(); //将object的方位角转化为四元数表示
object_list.objects[object_3_extended_id_].class_type = object_3_extended_->get_object_class(); //获取目标类别,0x0:point 0x1:car 0x2:truck 0x3:not in use 0x4:motorcycle 0x5:bicycle 0x6:wide 0x7:reserved
++object_3_extended_id_; //object_3_extended_id +1
}
}
6、自定义msg生成部分
-
之前radar_state_ros、cluster_list_ros、object_list_ros部分自定义了5种msg类型,ROS中对于自定义消息类型除了在msg文件夹下加入定义的 .msg文件外,还需要在 package.xml 中添加功能包依赖和在 CMakeLists.txt 文件中添加编译选项。
-
package.xml文件
<build_depend>message_generation</build_depend>
<build_export_depend>message_runtime</build_export_depend>
<exec_depend>message_runtime</exec_depend>
- CMakeLists.txt文件
find_package(... message_generation)
find_package(nav_msgs REQUIRED)
add_message_files(DIRECTORY msg
FILES
Cluster.msg
ClusterList.msg
Object.msg
ObjectList.msg
RadarStatus.msg
)
generate_messages(DEPENDENCIES std_msgs geometry_msgs)
catkin_package(
...
message_runtime
)
7、ars_40X_ros部分
-
前面几部分已经对雷达协议的各部分单独建立了服务或消息发布节点,那么需要发布的消息该从哪里获取以及这些节点又该如何启动呢。这里同样是采用封装的ARS_40X_ROS类来作为控制数据接收及解析后数据发送的主节点。
-
定义ARS_40X_ROS类(该类继承了ARS_40X_CAN协议接口类)
#ifndef ARS_40X_ARS_40X_ROS_HPP
#define ARS_40X_ARS_40X_ROS_HPP
#include <ros/ros.h>
#include <thread> //引入多线程库
#include "ars_40X/ros/cluster_list_ros.hpp" //发布cluster模式数据解析结果的头文件
#include "ars_40X/ros/motion_input_signals_ros.hpp" //获取及设置运动输入信号的头文件
#include "ars_40X/ros/object_list_ros.hpp" //发布object模式数据解析结果的头文件
#include "ars_40X/ros/radar_cfg_ros.hpp" //利用ROS中的srv服务通信对RadarCfg进行配置的头文件
#include "ars_40X/ros/radar_state_ros.hpp" //发布雷达状态信息解析结果的头文件
#include "ars_40X/ars_40X_can.hpp" //引入封装SocketCAN接口以及雷达协议接口类的头文件
namespace ars_40X {
class ARS_40X_ROS : public ARS_40X_CAN { //ROS节点类继承自ARS_40X_CAN接口类
public:
ARS_40X_ROS(ros::NodeHandle &nh); //有参构造函数,从外界获取节点句柄
~ARS_40X_ROS();
void receive_data();
void run(); //ROS控制节点的运行接口
void send_cluster_0_status();
void send_cluster_1_general();
void send_cluster_2_quality();
void send_object_0_status();
void send_object_1_general();
void send_object_2_quality();
void send_object_3_extended();
void send_radar_state(); //从ARS_40X_CAN接口类继承的虚函数,主要是通过调用各协议类中对应的send()函数来调用
private:
ros::NodeHandle nh_; //创建节点句柄
std::thread receive_data_thread_; //创建一个空的thread线程对象
ClusterListROS cluster_list_ros_;
MotionInputSignalsROS motion_input_signals_ros_;
ObjectListROS object_list_ros_;
RadarCfgROS radar_cfg_ros_;
RadarStateROS radar_state_ros_; //创建各部分处理协议解析结果的类对象
};
}
#endif //ARS_40X_ARS_40X_ROS_HPP
- ARS_40X_ROS类的实现
#include "ars_40X/ros/ars_40X_ros.hpp"
namespace ars_40X {
ARS_40X_ROS::ARS_40X_ROS(ros::NodeHandle &nh) :
nh_(nh), //从函数调用处获取节点句柄,并对变量初始化
cluster_list_ros_(nh_, this),
motion_input_signals_ros_(nh_, this),
object_list_ros_(nh_, this),
radar_cfg_ros_(nh_, this),
radar_state_ros_(nh_, this) { //利用参数列表对各部分处理协议解析结果的类对象初始化
ros::NodeHandle private_nh("~"); //创建私有命名空间的节点句柄,
std::string frame_id;
private_nh.param<std::string>("frame_id", frame_id, std::string("radar")); //从参数服务器获取 frame_id 的值赋给变量frame_id。如果无法获取,则将“radar”赋值给 frame_id
cluster_list_ros_.set_frame_id(frame_id);
object_list_ros_.set_frame_id(frame_id); //将 frame_id 传递给cluster_list_ros和object_list_ros部分
}
ARS_40X_ROS::~ARS_40X_ROS() {
}
void ARS_40X_ROS::receive_data() {
while (ros::ok()) { //检查节点是否正常运行
receive_radar_data(); //节点正常运行时调用协议接口类中的receive_radar_data()函数
}
}
void ARS_40X_ROS::send_cluster_0_status() { //继承自ARS_40X_CAN接口类的虚函数,主要是实现接口类中cluster_0_status部分数据解析及发布的函数
cluster_list_ros_.send_cluster_0_status();
}
void ARS_40X_ROS::send_cluster_1_general() { //继承自ARS_40X_CAN接口类的虚函数,主要是实现接口类中cluster_1_general部分数据解析及发布的函数
cluster_list_ros_.send_cluster_1_general();
}
void ARS_40X_ROS::send_cluster_2_quality() { //继承自ARS_40X_CAN接口类的虚函数,主要是实现接口类中cluster_2_quality部分数据解析及发布的函数
cluster_list_ros_.send_cluster_2_quality();
}
void ARS_40X_ROS::send_object_0_status() { //继承自ARS_40X_CAN接口类的虚函数,主要是实现接口类中object_0_status部分数据解析及发布的函数
object_list_ros_.send_object_0_status();
}
void ARS_40X_ROS::send_object_1_general() { //继承自ARS_40X_CAN接口类的虚函数,主要是实现接口类中object_1_general部分数据解析及发布的函数
object_list_ros_.send_object_1_general();
}
void ARS_40X_ROS::send_object_2_quality() { //继承自ARS_40X_CAN接口类的虚函数,主要是实现接口类中object_2_quality部分数据解析及发布的函数
object_list_ros_.send_object_2_quality();
}
void ARS_40X_ROS::send_object_3_extended() { //继承自ARS_40X_CAN接口类的虚函数,主要是实现接口类中object_3_extended部分数据解析及发布的函数
object_list_ros_.send_object_3_extended();
}
void ARS_40X_ROS::send_radar_state() { //继承自ARS_40X_CAN接口类的虚函数,主要是实现接口类中radar_state部分数据解析及发布的函数
radar_state_ros_.send_radar_state();
}
void ARS_40X_ROS::run() {
receive_data_thread_ = std::thread(std::bind(&ARS_40X_ROS::receive_data, this)); //std::bind()可以预先把指定可调用对象的某些参数绑定到已有的变量,生成一个新的可调用对象 std::thread()是用std::bind()返回的可调用对象来对线程对象实例化
receive_data_thread_.detach(); //开辟一条独立的线程,与主线程分离
}
}
int main(int argc, char **argv) {
ros::init(argc, argv, "ars_40X_ros"); //ROS节点初始化,节点名称为ars_40X_ros
ros::NodeHandle nh; //创建节点句柄nh
ars_40X::ARS_40X_ROS ars_40X_ros_(nh); //构建ARS_40X_ROS主节点类并进行初始化
ars_40X_ros_.run(); //调用线程来接收和处理雷达CAN口数据
ros::spin(); //开始订阅话题并产生回调
}
7、package.xml和CMakeLists.txt文件的组织
-
总的来说,之前提到的SocketCAN文件、雷达协议文件以及雷达数据解析发布文件等一系列接口调用最终是通过ROS节点来启动的。所有这些代码可以看做是ROS软件包的源码部分,而ROS软件包要想通过catkin编译运行的话,还需要一个符合catkin规范的package.xml文件和一个catkin版本的CMakeLists.txt文件。
-
package.xml文件
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3"> <!--在声明pacakge时指定format3, 为新版格式-->
<name>ars_40X</name> <!-- 包的名称-->
<version>0.0.0</version> <!-- 包的版本号(需要3个点分隔的整数)-->
<description>The ars_40X package contains a ROS driver for the Continental radar ARS_404 / ARS_408.</description> <!--包内容的描述-->
<maintainer email="org@gmail.com">org</maintainer> <!-- 维护包的人员的名称-->
<license>TODO: License declaration</license> <!--发布代码的软件许可证(例如GPL,BSD,ASL) -->
<buildtool_depend>catkin</buildtool_depend> <!-- 指定编译此功能包的编译系统工具-->
<build_depend>message_generation</build_depend> <!-- ,编译依赖项,编译时需要依赖的其它package,适用于静态库-->
<build_export_depend>message_runtime</build_export_depend> <!-- 导出依赖项-->
<depend>costmap_converter</depend>
<depend>geometry_msgs</depend>
<depend>nav_msgs</depend>
<depend>roscpp</depend>
<depend>socket_can</depend>
<depend>std_msgs</depend>
<depend>std_srvs</depend> <!-- 指定依赖项为编译、 导出、 运行需要的依赖-->
<exec_depend>message_runtime</exec_depend> <!-- 运行依赖项-->
<export> <!-- 用于添加额外的信息-->
<build_type>catkin</build_type>
</export>
</package>
- CMakeLists.txt文件
cmake_minimum_required(VERSION 3.5) # CMake版本
project(ars_40X) # 工程名
# Default to C99
if (NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif ()
# Default to C++14
if (NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif ()
if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif ()
# find dependencies,加载外部变量
find_package(catkin REQUIRED
COMPONENTS
roscpp
std_msgs
geometry_msgs
message_generation # 加载catkin中的变量,同时添加roscpp、std_msgs、geometry_msgs、message_generation的依赖
)
find_package(nav_msgs REQUIRED)
find_package(socket_can REQUIRED)
find_package(std_srvs REQUIRED)
find_package(Eigen3 REQUIRED) # 加载外部变量
add_message_files(DIRECTORY msg
FILES
Cluster.msg
ClusterList.msg
Object.msg
ObjectList.msg
RadarStatus.msg #添加自定义消息文件
)
add_service_files(
FILES
MaxDistance.srv
OutputType.srv
RadarPower.srv
RCSThreshold.srv
SensorID.srv
SortIndex.srv #添加自定义服务文件
)
generate_messages(DEPENDENCIES std_msgs geometry_msgs) #添加msg文件生成源代码文件时所需的依赖项
catkin_package( #catkin_package()是catkin提供的CMake宏,用于为catkin提供构建、生成pkg-config和CMake文件所需要的信息。
INCLUDE_DIRS # 声明给其它package的include路径
include
LIBRARIES # 声明给其它package的库
${PROJECT_NAME}_can
${PROJECT_NAME}_msg
CATKIN_DEPENDS #本包依赖的catkin package
message_runtime
roscpp
socket_can
)
include_directories(${catkin_INCLUDE_DIRS})
include_directories(include)
include_directories(${socket_can_INCLUDE_DIRS}) # 添加头文件路径: ${catkin_INCLUDE_DIRS}、include、${socket_can_INCLUDE_DIRS}
add_library(ars_40X_msg
src/cluster_list.cpp
src/motion_input_signals.cpp
src/object_list.cpp
src/radar_cfg.cpp
src/radar_state.cpp
) # 生成库文件,可传入多个源文件
add_library(ars_40X_can
src/ars_40X_can.cpp
) # 生成库文件,可传入多个源文件
target_link_libraries(ars_40X_can ars_40X_msg ${socket_can_LIBRARIES}) #为可执行文件或库添加链接库
add_executable(ars_40X_ros
src/ros/ars_40X_ros.cpp
src/ros/cluster_list_ros.cpp
src/ros/motion_input_signals_ros.cpp
src/ros/object_list_ros.cpp
src/ros/radar_cfg_ros.cpp
src/ros/radar_state_ros.cpp
) #生成可执行文件,可以传入多个源文件
add_dependencies(ars_40X_ros ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp) #为目标文件(add_executable(), add_library()中生成的)指定依赖,前提是已经通过find_package()引入了这个package
target_link_libraries(ars_40X_ros ${catkin_LIBRARIES}) #为可执行文件或库添加链接库,${catkin_LIBRARIES} 为ROS基本库
target_link_libraries(ars_40X_ros ars_40X_can ${catkin_LIBRARIES}) #为可执行文件或库添加链接库,${catkin_LIBRARIES} 为ROS基本库
install(
TARGETS
ars_40X_can
ars_40X_msg
ars_40X_ros
ARCHIVE DESTINATION lib/${PROJECT_NAME}
LIBRARY DESTINATION lib/${PROJECT_NAME}
RUNTIME DESTINATION lib/${PROJECT_NAME}
) #默认情况catkin会为每个package在./devel中建立目录,存放目标文件
# 目标文件可以直接通过rosrun和roslaunch访问
# 如需制定其它安装位置,则需通过install()命令