1、源程序
#include <ros/ros.h>
#include <sensor_msgs/JointState.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
#include <std_msgs/Float32.h>
#include <iostream>
#include <iomanip>
#include <boost/asio.hpp>
#include <boost/bind.hpp>
#include <math.h>
#include <QtNetwork/QUdpSocket>
#include <QObject>
#include <QtCore>
#include <QMutex>
#include "MotionControl.h"
using std::cout;
using std::endl;
using std::stringstream;
using std::string;
using namespace boost::asio;
using namespace std;
using namespace boost::asio; //定义一个命名空间,用于后面的读写操作
unsigned char buf[17]; //定义字符串长度,IMU返回的数据是17个字节一组,可用串口调试助手获得
int main(int argc, char** argv)
{
ros::init(argc, argv, "boost"); //初始化节点
ros::NodeHandle n;
ros::Publisher Motion_pub = n.advertise<std_msgs::Float32>("Motion_data", 1000); //定义发布消息的名称及sulv
ros::Rate loop_rate(100);
MotionControl MotionController;
MotionController.InitMotionBLS(2000,2000,500); //电机初始化
MotionController.TurnUp(500); //前进
QThread::sleep(5);
MotionController.MotionReadEncoderAndVel();
MotionController.MotionStop();
MotionController.TurnDown(500); //后退
QThread::sleep(5);
MotionController.MotionReadEncoderAndVel();
MotionController.MotionStop();
MotionController.TurnLeft(500); //左转
QThread::sleep(5);
MotionController.MotionReadEncoderAndVel();
MotionController.MotionStop();
MotionController.TurnRight(500); //右转
QThread::sleep(5);
MotionController.MotionReadEncoderAndVel();
MotionController.MotionStop();
MotionController.DisMotion();
while (ros::ok())
{
std_msgs::Float32 Motion_data;
Motion_pub.publish(Motion_data); //发布消息
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
2、MotionControl类头文件
#ifndef MOTIONCONTROL_H
#define MOTIONCONTROL_H
#include <QtNetwork/QUdpSocket>
#include <QObject>
#include <QtCore>
#include <QMutex>
#include "boost/thread.hpp"
#include "boost/asio.hpp"
using namespace std;
using namespace boost::asio;
class MotionControl
{
public:
MotionControl();
~MotionControl();
int add(int a,int b);
int multi(int a,int b);
void MotionConnect();//建立点对点UDP连接
void MotionModeSelect(int mode); //选择模式类型
void MotionErrorClear();//清除错误
void MotionSetAccVel(int num, int accVel);//设置加速度
void MotionSetDccVel(int num, int dccVel);//设置减速度
void MotionOffServo();//掉伺服
void MotionOnServo();//上伺服
void MotionSetVelocityValue(int num, int velocityValue);//设置速度
void MotionOpenVelocity();//开启速度
void MotionStop();//暂停
void MotionReadEncoderValue();//读编码值
void MotionReadEncoderAndVel();//读编码和速度
void InitMotionBLS(int accVel,int decVel,int vel);
void InitMotion(int accVel,int decVel,int vel);//启动初始化
void DisMotion();//停
void TurnLeft(int rotVel); //左转
void TurnRight(int rotVel);//右转
void TurnUp(int vel); //前进
void TurnDown(int vel); //后退
/*void ReadThread();*/
void DisConnect();
double GetYaw();
boost::system::error_code error;
//signals:
// void OutputMontionAndImu(int,int,int,int,double);
private:
io_service my_io_service;
ip::udp::endpoint remote_endpoint;
ip::udp::endpoint local_endpoint;
ip::udp::socket* socket;
QMutex mutex;
long posArray[2];
long velArray[2];
long array[4];
bool flag1;
bool flag2;
bool flag3;
bool flag4;
int mode;//模式
int accVel; //加速度
int decVel;//减速度
int lineVel;//速度
int rotVel;//原地旋转
int lineRotVel;//直线旋转
char recvBuf1[13];//接收数据的缓冲区
char recvBuf2[13];
double imuYaw;
};
#endif
3、MotionControl类成员函数和成员变量定义
#include "MotionControl.h"
#include <QWidget>
#include <QtNetwork/QUdpSocket>
#include <iostream>
#include <QThread>
#include "sys/stat.h"
using namespace std;
typedef unsigned short UINT16;
typedef unsigned long UINT32;
//QHostAddress *hostAddr=new QHostAddress("192.168.1.56");
//quint16 hostPort=4800;
//QHostAddress *goalAddr=new QHostAddress("192.168.1.56");
//quint16 goalPort=4001;
int axisNum = 2;
int MotionControl::add(int a,int b)
{
int c;
c = a+b;
return c;
}
int MotionControl::multi(int a,int b)
{
int c;
c = a*b;
return c;
}
MotionControl::MotionControl()
{
MotionConnect();
bool flag1=false;
bool flag2=false;
bool flag3=false;
bool flag4=false;
}
MotionControl::~MotionControl()
{
//lpmsNAVDisconnect();
}
//建立点对点UDP连接
void MotionControl::MotionConnect()
{
local_endpoint = ip::udp::endpoint(ip::address::from_string("192.168.1.55"), 4800);
remote_endpoint = ip::udp::endpoint(ip::address::from_string("192.168.1.101"), 4001);
//don't fill (ip::udp::v4()) in the first parameter,it will cause that the contents are seny out the failure!
socket = new ip::udp::socket(my_io_service, local_endpoint);//create socket and bind the endpoint
//bool imuState = lpmsNAVInit(9);
//lpmsNAVresetGyroStaticBias();
}
//选择模式类型
void MotionControl::MotionModeSelect(int mode)
{
for (int num = 1; num < axisNum+1; num++)
{
mutex.lock();
char mode_select_buf[] = {0x08,0x00,0x00,0x06,num,0x22,0x60,0x60,0x00,mode,0x00,0x00,0x00};
socket->send_to(buffer(mode_select_buf, sizeof(mode_select_buf) + 1), remote_endpoint);
mutex.unlock();
}
}
//清除错误
void MotionControl::MotionErrorClear()
{
for (int num = 1; num < axisNum+1; num++)
{
char error_clear_buf[] = { 0x08,0x00,0x00,0x06,num,0x22,0x40,0x60,0x00,0x80,0x00,0x00,0x00 };
mutex.lock();
socket->send_to(buffer(error_clear_buf, sizeof(error_clear_buf) + 1), remote_endpoint);
mutex.unlock();
}
}
//设置加速度
void MotionControl::MotionSetAccVel(int num,int accVel)
{
//高位后置
char high = accVel / 256;
char low = accVel % 256;
char acc_Vel_buf[] = {0x08,0x00,0x00,0x06,num,0x22,0x83,0x60,0x00,low,high,0x00,0x00};
mutex.lock();
socket->send_to(buffer(acc_Vel_buf, sizeof(acc_Vel_buf) + 1), remote_endpoint);
mutex.unlock();
}
//设置减速度
void MotionControl::MotionSetDccVel(int num, int dccVel)
{
//高位后置
char high = dccVel / 256;
char low = dccVel % 256;
char dcc_Vel_buf[] = { 0x08,0x00,0x00,0x06,num,0x22,0x84,0x60,0x00,low,high,0x00,0x00 };
mutex.lock();
socket->send_to(buffer(dcc_Vel_buf, sizeof(dcc_Vel_buf) + 1/*the size of contents*/), remote_endpoint);
mutex.unlock();
}
//掉伺服
void MotionControl::MotionOffServo()
{
for (int num = 1; num < axisNum+1; num++)
{
char off_Servo_buf[] = { 0x08,0x00,0x00,0x06,num,0x22,0x40,0x60,0x00,0x06,0x00,0x00,0x00 };
mutex.lock();
socket->send_to(buffer(off_Servo_buf, sizeof(off_Servo_buf) + 1), remote_endpoint);
mutex.unlock();
QThread::msleep(1);
}
}
//上伺服
void MotionControl::MotionOnServo()
{
for (int num = 1; num < axisNum+1; num++)
{
char on_Servo_buf[] = { 0x08,0x00,0x00,0x06,num,0x22,0x40,0x60,0x00,0x0F,0x00,0x00,0x00 };
mutex.lock();
socket->send_to(buffer(on_Servo_buf, sizeof(on_Servo_buf) + 1), remote_endpoint);
mutex.unlock();
}
}
//设置速度
void MotionControl::MotionSetVelocityValue(int num, int velocityValue)
{
unsigned char l1, l2, l3, l4;
//UINT16 high, low;
UINT16 high, low;
high = ((UINT32)(velocityValue)) / 65536;
low = ((UINT32)(velocityValue)) % 65536;
l1 = low / 256;
l2 = low % 256;
l3 = high / 256;
l4 = high % 256;
char set_VelocityValue_buf[] = { 0x08,0x00,0x00,0x06,num,0x22,0xFF,0x60,0x00,l2,l1,l4,l3 };
mutex.lock();
socket->send_to(buffer(set_VelocityValue_buf, sizeof(set_VelocityValue_buf) + 1), remote_endpoint);
mutex.unlock();
QThread::msleep(1);
}
//开启速度
void MotionControl::MotionOpenVelocity()
{
for (int num = 1; num < axisNum+1; num++)
{
char Open_Velocity_buf[] = { 0x08,0x00,0x00,0x06,num,0x22,0x40,0x60,0x00,0xF0,0x00,0x00,0x00 };
mutex.lock();
socket->send_to(buffer(Open_Velocity_buf, sizeof(Open_Velocity_buf) + 1), remote_endpoint);
mutex.unlock();
QThread::msleep(1);
}
}
//停止
void MotionControl::MotionStop()
{
for (int num = 1; num < axisNum+1; num++)
{
char stop_buf[] = { 0x08,0x00,0x00,0x06,num,0x22,0x40,0x60,0x00,0x0F,0x01,0x00,0x00 };
mutex.lock();
socket->send_to(buffer(stop_buf, sizeof(stop_buf) + 1), remote_endpoint);
mutex.unlock();
QThread::msleep(2);
}
}
//读编码值,读平均速度
void MotionControl::MotionReadEncoderAndVel()
{
UINT16 high_1, low_1;
unsigned char l1_1, l2_1, l3_1, l4_1;
UINT16 high_2, low_2;
unsigned char l1_2, l2_2, l3_2, l4_2;
int pos_1,pos_2;
char ss[12];
int Vel_1, Vel_2;
flag1=false;
flag2=false;
flag3=false;
flag4=false;
#pragma region 编码值提取
//右轮编码值提取
char read_CoderValue_buf_Right[] = { 0x08,0x00,0x00,0x06,0x01,0x40,0x64,0x60,0x00,0x00,0x00,0x00,0x00 };
socket->send_to(buffer(read_CoderValue_buf_Right, sizeof(read_CoderValue_buf_Right) + 1), remote_endpoint);
while (1)
{
socket->receive(boost::asio::buffer(recvBuf1), 0, error);
if (error && error != boost::asio::error::message_size)
throw boost::system::system_error(error);
if ( (recvBuf1)[3]==(char)0x05 && (recvBuf1)[5]==(char)0x43 && (recvBuf1)[6]==(char)0x64 && (recvBuf1)[7]==(char)0x60 && (recvBuf1)[8]==(char)0x00 && (recvBuf1)[4]==(char)0x81)
{
l2_1 = recvBuf1[9];
l1_1 = recvBuf1[10];
l4_1 = recvBuf1[11];
l3_1 = recvBuf1[12];
for (int i=0;i<4;i++)
{//右轮数据
ss[i] = recvBuf1[9 + i];
}
low_1 = l1_1 * 256 + l2_1;
high_1 = l3_1 * 256 + l4_1;
pos_1 = (int)(high_1 * 65536 + low_1);
posArray[0] = pos_1;
flag1=true;
break;
}
//数值提取转化
}
//左轮编码值提取
char read_CoderValue_buf_Left[] = {0x08,0x00,0x00,0x06,0x02,0x40,0x64,0x60,0x00,0x00,0x00,0x00,0x00 };
socket->send_to(buffer(read_CoderValue_buf_Left, sizeof(read_CoderValue_buf_Left) + 1), remote_endpoint);
while (1)
{
socket->receive(boost::asio::buffer(recvBuf1), 0, error);
if (error && error != boost::asio::error::message_size)
throw boost::system::system_error(error);
if ((recvBuf1)[3]==(char)0x05 && (recvBuf1)[5]==(char)0x43 && (recvBuf1)[6]==(char)0x64 && (recvBuf1)[7]==(char)0x60 && (recvBuf1)[8]==(char)0x00 && (recvBuf1)[4]==(char)0x82)
{
//数值提取转化
l2_2 = recvBuf1[9];
l1_2 = recvBuf1[10];
l4_2 = recvBuf1[11];
l3_2 = recvBuf1[12];
for (int i =4; i < 8; i++)
{//左轮数据
ss[i] = recvBuf1[5 + i];
}
low_2 = l1_2 * 256 + l2_2;
high_2 = l3_2 * 256 + l4_2;
pos_2 = (int)(high_2 * 65536 + low_2);
posArray[1] = pos_2;
flag2=true;
break;
}
}
//读平均速度
char read_AverageVel_buf_Right[] = { 0x08,0x00,0x00,0x06,0x01,0x40,0x28,0x20,0x00,0x00,0x00,0x00,0x00 };
socket->send_to(buffer(read_AverageVel_buf_Right, sizeof(read_AverageVel_buf_Right) + 1), remote_endpoint);
while (1)
{
socket->receive(boost::asio::buffer(recvBuf1), 0,error);
if (error && error != boost::asio::error::message_size)
throw boost::system::system_error(error);
if ((recvBuf1)[3]==(char)0x05 && (recvBuf1)[5]==(char)0x43 && (recvBuf1)[6]==(char)0x28 && (recvBuf1)[7]==(char)0x20 && (recvBuf1)[8]==(char)0x00 && (recvBuf1)[4]==(char)0x81)
{
//数值提取转化
l2_1 = recvBuf1[9];
l1_1 = recvBuf1[10];
l4_1 = recvBuf1[11];
l3_1 = recvBuf1[12];
for (int i = 0; i < 4; i++)
{//右轮数据
ss[i] = recvBuf1[9 + i];
}
low_1 = l1_1 * 256 + l2_1;
high_1 = l3_1 * 256 + l4_1;
Vel_1 = (int)(high_1 * 65536 + low_1);
velArray[0] = Vel_1;
flag3=true;
break;
}
}
//QThread::msleep(1);
char read_AverageVel_buf_Left[] = { 0x08,0x00,0x00,0x06,0x02,0x40,0x28,0x20,0x00,0x00,0x00,0x00,0x00 };
socket->send_to(buffer(read_AverageVel_buf_Left, sizeof(read_AverageVel_buf_Left) + 1), remote_endpoint);
while (1)
{
socket->receive(boost::asio::buffer(recvBuf1), 0, error);
if (error && error != boost::asio::error::message_size)
throw boost::system::system_error(error);
if ((recvBuf1)[3]==(char)0x05 && (recvBuf1)[5]==(char)0x43 && (recvBuf1)[6]==(char)0x28 && (recvBuf1)[7]==(char)0x20 && (recvBuf1)[8]==(char)0x00 && (recvBuf1)[4]==(char)0x82)
{
//数值提取转化
l2_2 = recvBuf1[9];
l1_2 = recvBuf1[10];
l4_2 = recvBuf1[11];
l3_2 = recvBuf1[12];
for (int i = 4; i < 8; i++)
{//左轮数据
ss[i] = recvBuf1[5 + i];
}
low_2 = l1_2 * 256 + l2_2;
high_2 = l3_2 * 256 + l4_2;
Vel_2 = (int)(high_2 * 65536 + low_2);
velArray[1] = Vel_2;
flag4=true;
break;
}
}
if (flag1 && flag2 && flag3 && flag4)
{
//显示编码及速度
array[0]=posArray[0];
array[1]=posArray[1];
array[2]=velArray[0];
array[3]=velArray[1];
cout << "pos0 = " << array[0] << endl;
cout << "pos1 = " << array[1] << endl;
cout << "vel0 = " << array[2] << endl;
cout << "vel1 = " << array[3] << endl;
//cout<<LpmsNAVGetData()<<endl;
//double yaw = LpmsNAVGetData()*M_PI/180;
//emit OutputMontionAndImu(array[0],array[1],array[2],array[3],(LpmsNAVGetData()*M_PI/180));
}
#pragma endregion
}
void MotionControl::InitMotionBLS(int accVel,int decVel,int vel)
{
QThread::msleep(4);
MotionErrorClear();
QThread::msleep(4);
MotionModeSelect(3);
QThread::msleep(4);
for (int num = 1; num < axisNum+1; num++)
{
MotionSetAccVel(num, accVel);
QThread::msleep(4);
}
for (int num = 1; num < axisNum+1; num++)
{
MotionSetDccVel(num, decVel);
QThread::msleep(4);
}
for (int num = 1; num < axisNum+1; num++)
{
MotionSetVelocityValue(num, vel);
QThread::msleep(4);
}
QThread::msleep(4);
MotionOffServo();
QThread::msleep(4);
MotionOnServo();
QThread::msleep(4);
}
//启动初始化
void MotionControl::InitMotion(int accVel,int decVel,int vel)
{
InitMotionBLS(accVel,decVel,vel);
}
void MotionControl::DisMotion()
{
MotionStop();
QThread::msleep(1);
MotionOffServo();
QThread::msleep(1);
}
//左转
void MotionControl::TurnLeft(int rotVel)
{
MotionSetVelocityValue(1, -rotVel);
MotionSetVelocityValue(2, -rotVel);
MotionOpenVelocity();
}
//右转
void MotionControl::TurnRight(int rotVel)
{
MotionSetVelocityValue(1, rotVel);
MotionSetVelocityValue(2, rotVel);
MotionOpenVelocity();
}
//前进
void MotionControl::TurnUp(int vel)
{
MotionSetVelocityValue(1, -vel);
QThread::msleep(2);
MotionSetVelocityValue(2, vel);
QThread::msleep(2);
MotionOpenVelocity();
QThread::msleep(2);
}
//后退
void MotionControl::TurnDown(int vel)
{
MotionSetVelocityValue(1, vel);
MotionSetVelocityValue(2, -vel);
MotionOpenVelocity();
}
// void MotionControl::ReadThread()
// {
// controlThread=new ControlThread();
// controlThreadstart();
// }
void MotionControl::DisConnect()
{
//lpmsNAVDisconnect();
socket->shutdown(boost::asio::socket_base::shutdown_type::shutdown_both);
}
double MotionControl::GetYaw()
{
//return (LpmsNAVGetData()*M_PI/180);
}
4、CMakelist文件
cmake_minimum_required(VERSION 2.8.3)
project(test)
## 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
sensor_msgs
cv_bridge
roscpp
std_msgs
image_transport
tf
# qt
)
add_definitions(-std=c++11)
find_package(Qt5Widgets)
find_package(Qt5Core)
find_package(Qt5Gui)
find_package(Qt5Network)
find_package( OpenCV REQUIRED )
## 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 run_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 run_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
# Message1.msg
# Message2.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 # Or other packages containing 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 run_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 you 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 test
# CATKIN_DEPENDS opencv roscpp
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
# include_directories(include)
include_directories(
${catkin_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${QT_INCLUDE_DIRS}
)
add_executable(MotionController src/MotionControl src/MotionController.cpp)
target_link_libraries(MotionController
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
Qt5::Widgets Qt5::Core Qt5::Gui
Qt5::Network
# ${QT_LIBRARIES}
)
## Declare a C++ library
# add_library(test
# src/${PROJECT_NAME}/test.cpp
# )
## 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(test ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
# add_executable(test_node src/test_node.cpp)
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(test_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(test_node
# ${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
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
# install(TARGETS test test_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_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_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)