相机和毫米波雷达数据融合4--解析模块代码编写

6 篇文章 2 订阅
2 篇文章 1 订阅

相机和毫米波雷达数据融合1–流程框架

相机和毫米波雷达数据融合2–SocketCan编写

相机和毫米波雷达数据融合3–Simulink解析Can信号

Simulink代码介绍

代码生成的文件介绍

在这里插入图片描述
这一共6个文件是你所需要移到你的Ros功能包下的。把头文件放在这个include文件夹中,cpp文件放在src里。

在这里插入图片描述
然后路径记得包含,检查一下有没有错误。

can_ros_class介绍

前面我们有介绍can_vehicle_class,用这个类我们可以实现can信号的收发。但是在收之后,发之前,我们需要利用simulink生成的代码来进行转换,而且里面的控制信息,和反馈信息应该是以ROS的msg存在于ROS网络中的,所以我们写一个can_ros_class类来完成这个。(这两个类能写一起吗?问问评论区c++大佬)下面以can0为例介绍这个。

can_ros_class.h

#ifndef CAN0_ROS_CLASS_H
#define CAN0_ROS_CLASS_H

#include <ros/ros.h>
#include "can0_node_test/Can0_to_msg.h"
#include "can0_node_test/Can0_to_param.h"
#include "can_vehicle_class.h"
#include "dbc_trans.h"

class Can0RosClass
{
private:
    ros::NodeHandle nh_;
    ros::Subscriber subscriber_;

    void InitSubscribers(CanVehicleClass& can_name,camera_dbcModelClass& rtObj);
    void InitPublishers();

public:
    static camera_dbcModelClass rtObj;
    Can0RosClass(ros::NodeHandle& nodehandle,char* name);
    CanVehicleClass can0_;
    ros::Publisher publisher_;
};

void Can0MsgSend_CommandMsg(const can0_node_test::Can0_to_msgConstPtr &can0_param,CanVehicleClass& can_name, camera_dbcModelClass& rtObj);
void Can0MsgReceive(Can0RosClass& Can0RosClass,ros::Publisher& pub,camera_dbcModelClass& rtObj);
#endif

这个类包含一个ros句柄(用来创建publisher和subscriber);一个publisher用来把解析后的到本车状态信息发出去;一个subscriber用来接收从其他节点传进来控制信息,然后调用相应的回调函数;一个静态类rtobj(simulink生成代码里的类,用来进行信号解析);一个CanVehicleClass(用来实现socketcan的功能)。一个publisher初始化函数;一个subscriber初始化函数,还有一个类构造函数。

之后还定义了两个函数分别是发送函数和接收函数。

can_ros_class.cpp

头文件包含

#include "can0_t/can0_ros_class.h"
#include "can0_t/dbc_trans.h"
#include "can0_node_test/Can0_to_msg.h"
#include "can0_node_test/Can0_to_param.h"

注意这里的头文件包含,有些头文件在头文件中的头文件已经被包含了,不用重复包含。第三个和第四个头文件在之后会详述。

Can0RosClass::Can0RosClass(params)

这是该类的构造函数。

Can0RosClass::Can0RosClass(ros::NodeHandle& nodehandle, char* name):nh_(nodehandle),can0_(name)
{
    ROS_INFO("in class constructor of Can0RosClass");
    InitSubscribers(this->can0_,this->rtObj);
    InitPublishers();
}

这个构造函数中完成了对can0_vehicle_class和Ros结点的构造,而前者在构造时就会完成Can_Init函数,也就是和相应的can口绑定。之后会创建相应的subscriber和publisher。

Can0RosClass::InitSubscribers(params)

void Can0RosClass::InitSubscribers(CanVehicleClass& can_name,camera_dbcModelClass& rtObj)
{
    ROS_INFO("Initializing Subscribers");
    subscriber_=nh_.subscribe<can0_node_test::Can0_to_msg>("Can0_to_msg",1,boost::bind(&Can0MsgSend_CommandMsg,_1,can0_,rtObj));
}

传入的参数是实现socketcan功能的CanVehicleClass类,还有实现信号解析的simulink代码生成的类。传入这两个参数是因为绑定的回调函数Can0MsgSend_CommandMsg需要这两个参数,后者把控制参数转换成can信号,前者把can信号发送出去。这里不太明白的话,可以去搜一下多参数回调函数ROS

Can0RosClass::InitPublishers()

void Can0RosClass::InitPublishers()
{
    ROS_INFO("Initializing Publishers");
    publisher_=nh_.advertise<can0_node_test::Can0_to_param>("Can0_to_param",1,true);
}

这个函数就是创建一个publisher,他会用来发布底盘的状态信号。

Can0_to_msg

我们来看看subscriber发送的msg格式是什么样的

float64 Gear_shift_req
float64 Steering_Pos_req
float64 Drive_Tq_Req
float64 Brake_Tq_Req
float64 Parking_Cmd

里面定义了需要的档位,需要的转向角度,需要的驱动力矩,需要的制动力矩,需要的制动指令。所以这个msg是从算法结点传进这个结点的,然后会调用回调函数,将这些信号打包成can信号发送出去。

Can0_to_param

再看看publisher发送出去的msg格式是什么样的

Header header
float64 C1_Host_velocity_vcu
float64 C1_Steering_angle
float64 C1_Gear_pos
float64 C1_Torque_fbk
float64 C3_Gear_Enb_fbk
float64 C3_Steering_Enb_fbk
float64 C3_Drive_Enb_fbk
float64 C3_Brake_Enb_fbk
float64 C3_Parking_Enb_fbk

定义了一个headr(里面有time stamp 后面时间同步需要用到),然后就是一系列的反馈信号。所以这么msg是这个结点将can信号解析之后,将信息赋值给这个msg得到的。他将被publish到其他结点去。

Can0MsgSend_CommandMsg(params)

void Can0MsgSend_CommandMsg(const can0_node_test::Can0_to_msgConstPtr &can0_param, CanVehicleClass& can_name, camera_dbcModelClass& rtObj)
{                            
        can_name.send_msg_vec.clear();
        //档位
        if(can0_param->Gear_shift_req > 0)
        {
            rtObj.rtU.Can0_Input_param.Gear_A1_Param1.Gear_Enable_control = 1;
            rtObj.rtU.Can0_Input_param.Gear_A1_Param1.Gear_Shift_Req = can0_param->Gear_shift_req;//01:驻车,02:空挡,03:前进,04:后退,05:无效
            rtObj.rtU.Can0_Input_param.Gear_A1_Param1.IPC_Mode_Shift = 0;
            rtObj.rtU.Can0_Input_param.Gear_A1_Param1.IPC_Stop_Eme = 0;
        }
        else
        {
            rtObj.rtU.Can0_Input_param.Gear_A1_Param1.Gear_Enable_control = 0;
            rtObj.rtU.Can0_Input_param.Gear_A1_Param1.Gear_Shift_Req = 0;
            rtObj.rtU.Can0_Input_param.Gear_A1_Param1.IPC_Mode_Shift = 0;
            rtObj.rtU.Can0_Input_param.Gear_A1_Param1.IPC_Stop_Eme = 0;
        }
        //转向
        if(can0_param->Steering_Pos_req > 0)
        {
            rtObj.rtU.Can0_Input_param.Steering_A2_Param1.Steering_Pos_Req = can0_param->Steering_Pos_req;//前轮转角-28到28
            rtObj.rtU.Can0_Input_param.Steering_A2_Param1.Steering_Enb = 1;
        }
        else
        {
            rtObj.rtU.Can0_Input_param.Steering_A2_Param1.Steering_Pos_Req = 0;
            rtObj.rtU.Can0_Input_param.Steering_A2_Param1.Steering_Enb = 0;
        }
        //驱动
        if(can0_param->Drive_Tq_Req > 0)
        {
            rtObj.rtU.Can0_Input_param.Drive_A3_Param1.Drive_Tq_Req = can0_param->Drive_Tq_Req;//驱动力矩百分比0-100
            rtObj.rtU.Can0_Input_param.Drive_A3_Param1.Drive_Enb = 1;
        }
        else
        {
            rtObj.rtU.Can0_Input_param.Drive_A3_Param1.Drive_Tq_Req = 0;
            rtObj.rtU.Can0_Input_param.Drive_A3_Param1.Drive_Enb = 0;
        }
        //制动
        if(can0_param->Brake_Tq_Req > 0)
        {
            rtObj.rtU.Can0_Input_param.Brake_A4_Param1.Brake_Enb = 1;
            rtObj.rtU.Can0_Input_param.Brake_A4_Param1.Brake_Tq_Req = can0_param->Brake_Tq_Req;//制动力矩百分比0-100
        }
        else
        {
            rtObj.rtU.Can0_Input_param.Brake_A4_Param1.Brake_Enb = 0;
            rtObj.rtU.Can0_Input_param.Brake_A4_Param1.Brake_Tq_Req = 0;
        }
        //驻车
        if(can0_param->Parking_Cmd > 0)
        {
            rtObj.rtU.Can0_Input_param.Parking_A5_Param1.Parking_Cmd = 1;
            rtObj.rtU.Can0_Input_param.Parking_A5_Param1.Parking_Enb = 1;
        }
        else
        {
            rtObj.rtU.Can0_Input_param.Parking_A5_Param1.Parking_Cmd = 0;
            rtObj.rtU.Can0_Input_param.Parking_A5_Param1.Parking_Enb = 0;
        }

        rtObj.step();//要重新设计dbc文件档位解析的那个。
        can_frame temp;
        //a1
        temp.can_id=rtObj.rtY.Can0_Gear_A1_Msg.ID;
        cout<<(int)temp.can_id<<endl;
        temp.can_dlc=rtObj.rtY.Can0_Gear_A1_Msg.Length;
        for(int i=0;i<rtObj.rtY.Can0_Gear_A1_Msg.Length;++i)
        {
            temp.data[i]=rtObj.rtY.Can0_Gear_A1_Msg.Data[i];
        }
        can_name.send_msg_vec.push_back(temp);

        //a2
        temp.can_id=rtObj.rtY.Can0_Steering_A2_Msg.ID;
        cout<<(int)temp.can_id<<endl;
        temp.can_dlc=rtObj.rtY.Can0_Steering_A2_Msg.Length;
        for(int i=0;i<rtObj.rtY.Can0_Steering_A2_Msg.Length;++i)
        {
            temp.data[i]=rtObj.rtY.Can0_Steering_A2_Msg.Data[i];
        }
        can_name.send_msg_vec.push_back(temp);

        //a3
        temp.can_id=rtObj.rtY.Can0_Drive_A3_Msg.ID;
        cout<<(int)temp.can_id<<endl;
        temp.can_dlc=rtObj.rtY.Can0_Drive_A3_Msg.Length;
        for(int i=0;i<rtObj.rtY.Can0_Drive_A3_Msg.Length;++i)
        {
            temp.data[i]=rtObj.rtY.Can0_Drive_A3_Msg.Data[i];
        }
        can_name.send_msg_vec.push_back(temp);

        //a4
        temp.can_id=rtObj.rtY.Can0_Brake_A4_Msg.ID;
        cout<<(int)temp.can_id<<endl;
        temp.can_dlc=rtObj.rtY.Can0_Brake_A4_Msg.Length;
        for(int i=0;i<rtObj.rtY.Can0_Brake_A4_Msg.Length;++i)
        {
            temp.data[i]=rtObj.rtY.Can0_Brake_A4_Msg.Data[i];
        }
        can_name.send_msg_vec.push_back(temp);

        //a5
        temp.can_id=rtObj.rtY.Can0_Parking_A5_Msg.ID;
        cout<<(int)temp.can_id<<endl;
        temp.can_dlc=rtObj.rtY.Can0_Parking_A5_Msg.Length;
        for(int i=0;i<rtObj.rtY.Can0_Parking_A5_Msg.Length;++i)
        {
            temp.data[i]=rtObj.rtY.Can0_Parking_A5_Msg.Data[i];
        }
        can_name.send_msg_vec.push_back(temp);

        can_name.Can_Send_Msg(can_name.send_msg_vec);

}

这段代码的思路就是,把传递进来的can0_param(他是can0_to_msg格式哦)里的指令信息进行判断,然后赋值给rtobj.rtU(这是表示simulink模块的输入),赋值好之后,运行rtobj.step(),你可以理解为让这个simulink模块运行。然后就可以得到输出,输出就是你需要的can信号,你需要把这些can信号,push到CanVehicleClass里的成员变量–send_msg_vec中去。我没有试过直接push模型的输出can_msg。上面的代码我用一个临时变量temp来赋值,然后再输入。注意每次进入这个回调函数要把send_msg_vec先清空。

Can0MsgReceive(params)

void Can0MsgReceive(Can0RosClass& Can0RosClass,ros::Publisher& pub,camera_dbcModelClass& rtObj)
{
    while(ros::ok())
    {
        Can0RosClass.can0_.CAN_Receive_Msg(Can0RosClass.can0_.receive_msg,Can0RosClass.can0_.receive_id_vec);//id是底盘信号id:0c1 0c3

        if(Can0RosClass.can0_.receive_msg.can_id == 0xC1)
        {
            rtObj.rtU.Can0_Enable_C3_Msg.ID = Can0RosClass.can0_.receive_msg.can_id;
            rtObj.rtU.Can0_Vcu_C1_Msg.Length = Can0RosClass.can0_.receive_msg.can_dlc;
            for(int i = 0; i < Can0RosClass.can0_.receive_msg.can_dlc; ++i)
            {
                rtObj.rtU.Can0_Vcu_C1_Msg.Data[i] = (int)Can0RosClass.can0_.receive_msg.data[i];
            }
        }

        if(Can0RosClass.can0_.receive_msg.can_id == 0xC3)
        {
            rtObj.rtU.Can0_Enable_C3_Msg.ID = Can0RosClass.can0_.receive_msg.can_id;
            rtObj.rtU.Can0_Enable_C3_Msg.Length = Can0RosClass.can0_.receive_msg.can_dlc;
            for(int i = 0; i < Can0RosClass.can0_.receive_msg.can_dlc; ++i)
            {
                rtObj.rtU.Can0_Enable_C3_Msg.Data[i] = (int)Can0RosClass.can0_.receive_msg.data[i];
            }
        }

        //写if判断加入所有该can的输入rtobj
        // gettimeofday(&t,NULL);
        // cout << t.tv_sec * 1000 + t.tv_usec / 1000 << " ";
        // cout << Can0RosClass.can0_.receive_msg.can_id << " ";
        rtObj.step();
        can0_node_test::Can0_to_param can0_to_param;
        ++can0_to_param.header.seq;
        can0_to_param.header.stamp = ros::Time::now();
        can0_to_param.C1_Host_velocity_vcu = rtObj.rtY.Can0_Vcu_C1_Param.Vehicle_Spd;
        can0_to_param.C1_Steering_angle = rtObj.rtY.Can0_Vcu_C1_Param.Steering_Ang;
        can0_to_param.C1_Gear_pos = rtObj.rtY.Can0_Vcu_C1_Param.Gear_Pos;
        can0_to_param.C1_Torque_fbk = rtObj.rtY.Can0_Vcu_C1_Param.Torque_fbk;
        can0_to_param.C3_Brake_Enb_fbk = rtObj.rtY.Can0_Enable_C3_Param.Brake_Enb_fbk;
        can0_to_param.C3_Drive_Enb_fbk = rtObj.rtY.Can0_Enable_C3_Param.Drive_Enb_fbk;
        can0_to_param.C3_Gear_Enb_fbk = rtObj.rtY.Can0_Enable_C3_Param.Gear_Enb_fbk;
        can0_to_param.C3_Parking_Enb_fbk = rtObj.rtY.Can0_Enable_C3_Param.Parking_Enb_fbk;
        can0_to_param.C3_Steering_Enb_fbk = rtObj.rtY.Can0_Enable_C3_Param.Steering_Enb_fbk;
        // cout << rtObj.rtY.BMS_feedback[1] <<endl;
        if(Can0RosClass.can0_.receive_msg.can_id==0xC3)pub.publish(can0_to_param);
        // r.sleep();
        // cout << rtObj.rtY.BMS_feedback_l.Current << endl;
        ros::spinOnce();
    }
}

这个函数思路要不停接收传进来的can信号,然后解析,所以要有一个ros::ok()来一直运行这个结点,通过过滤id,对id进行判断,然后把can信号赋值给simulink的输入,运行rtobj.step()得到输出,然后用can0_to_param来接收这些输出,最后把这个msg发送到ros网络中。

can0_test.cpp

#include "can0_t/can0_ros_class.h"

camera_dbcModelClass Can0RosClass::rtObj;


int main(int argc, char* argv[])
{

    ros::init(argc, argv, "can0_test_node");
    ros::NodeHandle nh;
    char can0_name[5] = "can0";
    Can0RosClass can0_ros_class(nh,can0_name);
    can0_ros_class.rtObj.initialize();
    can0_ros_class.can0_.receive_id_vec={0x0C1,0x0C3};

    Can0MsgReceive(can0_ros_class, can0_ros_class.Soc_publisher_, can0_ros_class.rtObj);
    // ros::spin();
    return 0;
}

这是主节点源文件。比较简单,运行之后会进入Can0MsgReceive函数中,至于发送函数,是通过回调函数,会在收到相应的can0_to_msg被调用。

cmakelist文件

cmake_minimum_required(VERSION 3.0.2)
project(can0_node_test)

## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  std_msgs
  message_generation
)

## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)


## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()

################################################
## Declare ROS messages, services and actions ##
################################################

## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
##   * add a build_depend tag for "message_generation"
##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in
##     but can be declared for certainty nonetheless:
##     * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
##   * add "message_generation" and every package in MSG_DEP_SET to
##     find_package(catkin REQUIRED COMPONENTS ...)
##   * add "message_runtime" and every package in MSG_DEP_SET to
##     catkin_package(CATKIN_DEPENDS ...)
##   * uncomment the add_*_files sections below as needed
##     and list every .msg/.srv/.action file to be processed
##   * uncomment the generate_messages entry below
##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)

## Generate messages in the 'msg' folder
add_message_files(
  FILES
  Can0_to_msg.msg
  Can0_to_param.msg
)

## Generate services in the 'srv' folder
# add_service_files(
#   FILES
#   Service1.srv
#   Service2.srv
# )

## Generate actions in the 'action' folder
# add_action_files(
#   FILES
#   Action1.action
#   Action2.action
# )

## Generate added messages and services with any dependencies listed here
generate_messages(
  DEPENDENCIES
  std_msgs
)

################################################
## Declare ROS dynamic reconfigure parameters ##
################################################

## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
##   * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
##   * add "dynamic_reconfigure" to
##     find_package(catkin REQUIRED COMPONENTS ...)
##   * uncomment the "generate_dynamic_reconfigure_options" section below
##     and list every .cfg file to be processed

## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
#   cfg/DynReconf1.cfg
#   cfg/DynReconf2.cfg
# )

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
 INCLUDE_DIRS include
 LIBRARIES can0_t
 CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
#  DEPENDS system_lib
)

###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
 include
  ${catkin_INCLUDE_DIRS}
)

## Declare a C++ library
add_library(can0_t
  src/dbc_trans.cpp
  src/dbc_trans_data.cpp
  src/can_vehicle_class.cpp
  src/can0_ros_class.cpp
  # include/can0_t/can_message.h 
  # include/can0_t/dbc_trans.h
  # include/can0_t/rtwtypes.h
  # include/can0_t/tmwtypes.h 
  # include/can0_t/can_vehicle_class.h
  # include/can0_t/can0_ros_class.h 
)

## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
add_dependencies(can0_t ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
add_executable(gear_pub src/gear_pub.cpp)
add_executable(soc_sub src/soc_sub.cpp)
add_executable(can0_test src/can0_test.cpp)

## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")

## Add cmake target dependencies of the executable
## same as for the library above
add_dependencies(gear_pub ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(soc_sub ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(can0_test ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})


## Specify libraries to link a library or executable target against
target_link_libraries(gear_pub
  ${catkin_LIBRARIES}
)
target_link_libraries(soc_sub
${catkin_LIBRARIES}
)
target_link_libraries(can0_t
${catkin_LIBRARIES}
)
target_link_libraries(can0_test can0_t
${catkin_LIBRARIES}
)
#############
## Install ##
#############

# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html

## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
#   scripts/my_python_script
#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )

## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
#   FILES_MATCHING PATTERN "*.h"
#   PATTERN ".svn" EXCLUDE
# )

## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
#   # myfile1
#   # myfile2
#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )

#############
## Testing ##
#############

## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_can0_node_test.cpp)
# if(TARGET ${PROJECT_NAME}-test)
#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()

## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

package.xml文件

<?xml version="1.0"?>
<package format="2">
  <name>can0_node_test</name>
  <version>0.0.0</version>
  <description>The can0_node_test package</description>

  <!-- One maintainer tag required, multiple allowed, one person per tag -->
  <!-- Example:  -->
  <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
  <maintainer email="aa@todo.todo">aa</maintainer>


  <!-- One license tag required, multiple allowed, one license per tag -->
  <!-- Commonly used license strings: -->
  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
  <license>TODO</license>


  <!-- Url tags are optional, but multiple are allowed, one per tag -->
  <!-- Optional attribute type can be: website, bugtracker, or repository -->
  <!-- Example: -->
  <!-- <url type="website">http://wiki.ros.org/can0_node_test</url> -->


  <!-- Author tags are optional, multiple are allowed, one per tag -->
  <!-- Authors do not have to be maintainers, but could be -->
  <!-- Example: -->
  <!-- <author email="jane.doe@example.com">Jane Doe</author> -->


  <!-- The *depend tags are used to specify dependencies -->
  <!-- Dependencies can be catkin packages or system dependencies -->
  <!-- Examples: -->
  <!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
  <!--   <depend>roscpp</depend> -->
  <!--   Note that this is equivalent to the following: -->
  <!--   <build_depend>roscpp</build_depend> -->
  <!--   <exec_depend>roscpp</exec_depend> -->
  <!-- Use build_depend for packages you need at compile time: -->
  <!--   <build_depend>message_generation</build_depend> -->
  <!-- Use build_export_depend for packages you need in order to build against this package: -->
  <!--   <build_export_depend>message_generation</build_export_depend> -->
  <!-- Use buildtool_depend for build tool packages: -->
  <!--   <buildtool_depend>catkin</buildtool_depend> -->
  <!-- Use exec_depend for packages you need at runtime: -->
  <!--   <exec_depend>message_runtime</exec_depend> -->
  <!-- Use test_depend for packages you need only for testing: -->
  <!--   <test_depend>gtest</test_depend> -->
  <!-- Use doc_depend for packages you need only for building documentation: -->
  <!--   <doc_depend>doxygen</doc_depend> -->
  <buildtool_depend>catkin</buildtool_depend>
  <build_depend>roscpp</build_depend>
  <build_depend>rospy</build_depend>
  <build_depend>std_msgs</build_depend>
  <build_depend>message_generation</build_depend>
  <build_export_depend>roscpp</build_export_depend>
  <build_export_depend>rospy</build_export_depend>
  <build_export_depend>std_msgs</build_export_depend>
  <exec_depend>roscpp</exec_depend>
  <exec_depend>rospy</exec_depend>
  <exec_depend>std_msgs</exec_depend>
  <exec_depend>message_runtime</exec_depend>


  <!-- The export tag contains other, unspecified, tags -->
  <export>
    <!-- Other tools can request additional information be placed here -->

  </export>
</package>

总结

写完这篇文章,忽然发现有很多地方的定义和传参我都有些不确定。但是思路肯定是没问题的。后续我会再进行优化,验证,对文章进行修改。

  • 3
    点赞
  • 16
    收藏
    觉得还不错? 一键收藏
  • 2
    评论
评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值