add msg publish and convert 3dbox to 2d
This commit is contained in:
parent
d5cc3aae62
commit
7e1439f240
@ -27,6 +27,7 @@ find_package(catkin REQUIRED COMPONENTS
|
||||
pcl_ros
|
||||
image_transport
|
||||
cv_bridge
|
||||
perception_msgs
|
||||
)
|
||||
find_package(yaml-cpp REQUIRED)
|
||||
|
||||
@ -180,6 +181,7 @@ add_executable(${PROJECT_NAME}_node src/main.cpp src/postprocess.cc src/preproc
|
||||
## Add cmake target dependencies of the executable
|
||||
## same as for the library above
|
||||
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
add_dependencies(${PROJECT_NAME}_node perception_msgs_gencpp)
|
||||
|
||||
## Specify libraries to link a library or executable target against
|
||||
target_link_libraries(${PROJECT_NAME}_node
|
||||
|
60
src/guangpo_yolo_lidar/include/message.hpp
Normal file
60
src/guangpo_yolo_lidar/include/message.hpp
Normal file
@ -0,0 +1,60 @@
|
||||
#pragma once
|
||||
|
||||
#include <perception_msgs/PerceptionObstacle.h>
|
||||
#include <perception_msgs/PerceptionObstacles.h>
|
||||
|
||||
#include "yolo_lidar_help.hpp"
|
||||
|
||||
inline perception_msgs::PerceptionObstacles
|
||||
PackageMessage(const std::vector<mybox> &box3ds, bool verbose = false) {
|
||||
static auto SetValue = [](geometry_msgs::Point &des, const cv::Point2f &src) {
|
||||
des.x = src.x;
|
||||
des.y = src.y;
|
||||
des.z = 0;
|
||||
};
|
||||
|
||||
perception_msgs::PerceptionObstacles obstacles;
|
||||
|
||||
for (int i = 0; i < box3ds.size(); i++) {
|
||||
auto &box = box3ds[i];
|
||||
perception_msgs::PerceptionObstacle obstacle;
|
||||
obstacle.label = box.label;
|
||||
// 如果聚类失败了(点太少或者不满足要求)
|
||||
if (box.lidar_cluster->points.empty()) {
|
||||
continue;
|
||||
}
|
||||
SetValue(obstacle.center_point, box.position.center);
|
||||
obstacle.corner_points.resize(4);
|
||||
SetValue(obstacle.corner_points.at(0), box.position.vertices.at(0));
|
||||
SetValue(obstacle.corner_points.at(1), box.position.vertices.at(1));
|
||||
SetValue(obstacle.corner_points.at(2), box.position.vertices.at(2));
|
||||
SetValue(obstacle.corner_points.at(3), box.position.vertices.at(3));
|
||||
obstacles.obstacles.emplace_back(std::move(obstacle));
|
||||
}
|
||||
if (verbose) {
|
||||
for (int i = 0; i < obstacles.obstacles.size(); i++) {
|
||||
auto &obst = obstacles.obstacles.at(i);
|
||||
gDebug() << VAR("obstacle", i, obst.label);
|
||||
gDebug() << VAR(obst.center_point.x, obst.center_point.y);
|
||||
gDebug() << VAR(obst.corner_points.at(0).x, obst.corner_points.at(0).y);
|
||||
gDebug() << VAR(obst.corner_points.at(1).x, obst.corner_points.at(1).y);
|
||||
gDebug() << VAR(obst.corner_points.at(2).x, obst.corner_points.at(2).y);
|
||||
gDebug() << VAR(obst.corner_points.at(3).x, obst.corner_points.at(3).y);
|
||||
}
|
||||
}
|
||||
return obstacles;
|
||||
}
|
||||
|
||||
inline std::vector<std::vector<cv::Point2f>>
|
||||
Package2dBoxMarker(const std::vector<mybox> &box3ds) {
|
||||
std::vector<std::vector<cv::Point2f>> res;
|
||||
for (int i = 0; i < box3ds.size(); i++) {
|
||||
auto &box = box3ds[i];
|
||||
// 如果聚类失败了(点太少或者不满足要求)
|
||||
if (box.lidar_cluster->points.empty()) {
|
||||
continue;
|
||||
}
|
||||
res.push_back(box.position.vertices);
|
||||
}
|
||||
return res;
|
||||
}
|
@ -6,6 +6,7 @@
|
||||
#include <message_filters/sync_policies/approximate_time.h>
|
||||
#include <message_filters/time_synchronizer.h>
|
||||
#include <opencv2/core/eigen.hpp>
|
||||
#include <opencv2/imgproc.hpp>
|
||||
#include <opencv2/opencv.hpp>
|
||||
#include <ros/ros.h>
|
||||
#include <sensor_msgs/Image.h>
|
||||
@ -41,6 +42,12 @@ inline Eigen::Matrix4d TransforMatrix(const Eigen::Vector3d &translation,
|
||||
// std::endl;
|
||||
return transformation_matrix;
|
||||
}
|
||||
|
||||
struct MinAreaRectInfo {
|
||||
cv::Point2f center;
|
||||
std::vector<cv::Point2f> vertices;
|
||||
};
|
||||
|
||||
struct mybox {
|
||||
mybox()
|
||||
: lidar_points(new pcl::PointCloud<pcl::PointXYZ>),
|
||||
@ -54,10 +61,13 @@ struct mybox {
|
||||
Eigen::Vector3f obstacle_centroids;
|
||||
Eigen::Vector3f obstacle_sizes;
|
||||
Eigen::Quaternionf obstacle_orientations;
|
||||
// 对应到机体坐标系上的点
|
||||
MinAreaRectInfo position;
|
||||
|
||||
// 拷贝构造函数
|
||||
mybox(const mybox &other)
|
||||
: label(other.label), rect(other.rect), small_rect(other.small_rect),
|
||||
position(other.position),
|
||||
lidar_points(new pcl::PointCloud<pcl::PointXYZ>(*other.lidar_points)),
|
||||
lidar_cluster(new pcl::PointCloud<pcl::PointXYZ>(*other.lidar_cluster)),
|
||||
obstacle_centroids(other.obstacle_centroids),
|
||||
@ -70,6 +80,8 @@ struct mybox {
|
||||
label = other.label;
|
||||
rect = other.rect;
|
||||
small_rect = other.small_rect;
|
||||
|
||||
position = other.position,
|
||||
lidar_points.reset(
|
||||
new pcl::PointCloud<pcl::PointXYZ>(*other.lidar_points));
|
||||
lidar_cluster.reset(
|
||||
@ -84,6 +96,8 @@ struct mybox {
|
||||
// 移动构造函数
|
||||
mybox(mybox &&other) noexcept
|
||||
: label(std::move(other.label)), rect(std::move(other.rect)),
|
||||
|
||||
position(std::move(other.position)),
|
||||
small_rect(std::move(other.small_rect)),
|
||||
lidar_points(std::move(other.lidar_points)),
|
||||
lidar_cluster(std::move(other.lidar_cluster)),
|
||||
@ -97,6 +111,7 @@ struct mybox {
|
||||
label = std::move(other.label);
|
||||
rect = std::move(other.rect);
|
||||
small_rect = std::move(other.small_rect);
|
||||
position = std::move(other.position),
|
||||
lidar_points = std::move(other.lidar_points);
|
||||
lidar_cluster = std::move(other.lidar_cluster);
|
||||
obstacle_centroids = std::move(other.obstacle_centroids);
|
||||
@ -107,6 +122,27 @@ struct mybox {
|
||||
}
|
||||
};
|
||||
|
||||
// 获取一个3维点云的最小的矩形
|
||||
inline MinAreaRectInfo GetMinAreaRectInfoFrom3DCloud(
|
||||
const pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud) {
|
||||
std::vector<cv::Point2f> points;
|
||||
for (const auto &point : cloud->points) {
|
||||
points.emplace_back(point.x, point.y);
|
||||
}
|
||||
cv::RotatedRect rect = cv::minAreaRect(points);
|
||||
|
||||
MinAreaRectInfo info;
|
||||
info.center = rect.center;
|
||||
|
||||
cv::Point2f vertices[4];
|
||||
rect.points(vertices);
|
||||
for (int i = 0; i < 4; i++) {
|
||||
info.vertices.push_back(vertices[i]);
|
||||
}
|
||||
|
||||
return info;
|
||||
}
|
||||
|
||||
// 把点云去除地面相关点
|
||||
// 返回值第一个是非地面点,第二个是地面点
|
||||
template <typename PointT>
|
||||
@ -303,8 +339,11 @@ public:
|
||||
convert_camera2lidar_ = Camera2Lidar();
|
||||
gDebugCol5(convert_camera2lidar_);
|
||||
// 初始化雷达到车体位姿
|
||||
convert_lidar2car_ = Lidar2Car();
|
||||
gDebugCol5(convert_lidar2car_);
|
||||
auto get = Lidar2Car();
|
||||
convert_lidar2car_matrix_ = get.first;
|
||||
convert_lidar2car_affine_ = get.second;
|
||||
gDebugCol5(convert_lidar2car_matrix_);
|
||||
gDebugCol5(convert_lidar2car_affine_);
|
||||
|
||||
{
|
||||
Eigen::Affine3d convert_point_cl = Eigen::Affine3d(
|
||||
@ -316,10 +355,11 @@ public:
|
||||
all_in_one_matrix_ = camera_inner_eigen * xyz2zyx * convert_point_cl;
|
||||
}
|
||||
}
|
||||
cv::Mat camera_inner_matrix_; // 相机内参矩阵
|
||||
cv::Mat camera_distort_matrix_; // 相机畸变参数矩阵
|
||||
Eigen::Matrix4d convert_camera2lidar_; // 相机到雷达的位姿转换
|
||||
Eigen::Matrix4d convert_lidar2car_; // 雷达到车的位姿转换
|
||||
cv::Mat camera_inner_matrix_; // 相机内参矩阵
|
||||
cv::Mat camera_distort_matrix_; // 相机畸变参数矩阵
|
||||
Eigen::Matrix4d convert_camera2lidar_; // 相机到雷达的位姿转换
|
||||
Eigen::Matrix4d convert_lidar2car_matrix_; // 雷达到车的位姿转换
|
||||
Eigen::Affine3f convert_lidar2car_affine_; // 雷达到车的位姿转换
|
||||
|
||||
Eigen::Affine3d all_in_one_matrix_; // 激光点到相机像素坐标系点
|
||||
public:
|
||||
@ -380,7 +420,7 @@ private:
|
||||
// 转换为Affine3f类型 affine3f_transform = affine3f_transform.inverse();
|
||||
return tran_matrix;
|
||||
}
|
||||
inline Eigen::Matrix4d Lidar2Car() {
|
||||
inline std::pair<Eigen::Matrix4d, Eigen::Affine3f> Lidar2Car() {
|
||||
// 初始化坐标系变换的旋转矩阵
|
||||
Eigen::Vector3d trans;
|
||||
trans[0] = yaml_config["convert_lidar2car"]["transform"]["x"].as<double>();
|
||||
@ -402,9 +442,10 @@ private:
|
||||
Eigen::Matrix4d tran_matrix = TransforMatrix(
|
||||
trans, roll * M_PI / 180.0, pitch * M_PI / 180.0, yaw * M_PI / 180.0);
|
||||
gDebug() << VAR(tran_matrix);
|
||||
// Eigen::Affine3d affine3d_transform(tran_matrix); // 转换为Affine3d类型
|
||||
// affine3f_transform = affine3d_transform.cast<float>(); //
|
||||
// 转换为Affine3f类型 affine3f_transform = affine3f_transform.inverse();
|
||||
return tran_matrix;
|
||||
Eigen::Affine3d affine3d_transform(tran_matrix); // 转换为Affine3d类型
|
||||
Eigen::Affine3f affine3f_transform = affine3d_transform.cast<float>(); //
|
||||
// 转换为Affine3f类型
|
||||
affine3f_transform = affine3f_transform.inverse();
|
||||
return {tran_matrix, affine3f_transform};
|
||||
}
|
||||
};
|
||||
|
@ -67,6 +67,9 @@
|
||||
<exec_depend>rospy</exec_depend>
|
||||
<exec_depend>sensor_msgs</exec_depend>
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
<build_depend>perception_msgs</build_depend>
|
||||
<!-- <build_export_depend>perception_msgs</run_depend> -->
|
||||
<exec_depend>perception_msgs</exec_depend>
|
||||
|
||||
|
||||
<!-- The export tag contains other, unspecified, tags -->
|
||||
|
@ -1,5 +1,6 @@
|
||||
#include <cv_bridge/cv_bridge.h>
|
||||
#include <filesystem>
|
||||
#include <geometry_msgs/PolygonStamped.h>
|
||||
#include <message_filters/subscriber.h>
|
||||
#include <message_filters/sync_policies/approximate_time.h>
|
||||
#include <message_filters/time_synchronizer.h>
|
||||
@ -12,13 +13,18 @@
|
||||
#include <visualization_msgs/Marker.h>
|
||||
#include <visualization_msgs/MarkerArray.h>
|
||||
|
||||
#include <pcl/common/transforms.h>
|
||||
#include <pcl/filters/voxel_grid.h>
|
||||
#include <pcl/point_cloud.h>
|
||||
#include <pcl/point_types.h>
|
||||
#include <pcl_conversions/pcl_conversions.h>
|
||||
|
||||
#include <perception_msgs/PerceptionObstacle.h>
|
||||
#include <perception_msgs/PerceptionObstacles.h>
|
||||
|
||||
#include "dbscan.hpp"
|
||||
#include "debugstream.hpp"
|
||||
#include "message.hpp"
|
||||
#include "yaml_config.h"
|
||||
#include "yolo_lidar_help.hpp"
|
||||
|
||||
@ -95,6 +101,9 @@ public:
|
||||
yolo_other.SetLabels(labels_other);
|
||||
yolo_other.LoadModel(model_other_name);
|
||||
|
||||
pub_obstacles_ = nh.advertise<perception_msgs::PerceptionObstacles>(
|
||||
yaml_config["obstacles_topic_"].as<std::string>(), 10);
|
||||
|
||||
person_density_pub_ = nh.advertise<std_msgs::Int8>(
|
||||
yaml_config["person_density_topic"].as<std::string>(), 10);
|
||||
|
||||
@ -184,11 +193,17 @@ public:
|
||||
ROS_INFO("Image published!");
|
||||
}
|
||||
|
||||
// 输入的点云是激光坐标系下的,发布的是车辆坐标系
|
||||
void SendLidar(ros::Publisher &pub,
|
||||
const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) {
|
||||
pcl::PointCloud<pcl::PointXYZ>::Ptr publish(
|
||||
new pcl::PointCloud<pcl::PointXYZ>);
|
||||
// 将点云进行转换
|
||||
pcl::transformPointCloud(*cloud, *publish, help.convert_lidar2car_affine_);
|
||||
|
||||
// 发送点云数组
|
||||
sensor_msgs::PointCloud2 msg;
|
||||
pcl::toROSMsg(*cloud, msg);
|
||||
pcl::toROSMsg(*publish, msg);
|
||||
msg.header.frame_id = "map"; // 设置坐标系
|
||||
msg.header.stamp = ros::Time::now();
|
||||
pub.publish(msg);
|
||||
@ -271,6 +286,48 @@ public:
|
||||
|
||||
pub_3dbox_.publish(marker_array);
|
||||
}
|
||||
void Publish2dObstacles(
|
||||
const std::vector<std::vector<cv::Point2f>> &obstacle_polygons) {
|
||||
visualization_msgs::MarkerArray marker_array;
|
||||
|
||||
// 首先发布一个DELETEALL命令,删除上次发布的所有障碍物标记
|
||||
visualization_msgs::Marker delete_marker;
|
||||
delete_marker.header.frame_id = "map";
|
||||
delete_marker.action = visualization_msgs::Marker::LINE_STRIP;
|
||||
marker_array.markers.push_back(delete_marker);
|
||||
pub_3dbox_.publish(marker_array);
|
||||
marker_array.markers.clear(); // 清空marker_array
|
||||
|
||||
for (size_t i = 0; i < obstacle_polygons.size(); ++i) {
|
||||
visualization_msgs::Marker marker;
|
||||
marker.header.frame_id = "map";
|
||||
marker.type = visualization_msgs::Marker::LINE_STRIP;
|
||||
marker.action = visualization_msgs::Marker::ADD;
|
||||
marker.id = i;
|
||||
marker.scale.x = 0.1;
|
||||
marker.pose.orientation.w = 1.0; // 朝向为单位四元数
|
||||
marker.color.r = 1.0f;
|
||||
marker.color.g = 0.0f;
|
||||
marker.color.b = 0.0f;
|
||||
marker.color.a = 0.3;
|
||||
|
||||
geometry_msgs::Point p;
|
||||
for (const auto &point : obstacle_polygons[i]) {
|
||||
p.x = point.x;
|
||||
p.y = point.y;
|
||||
p.z = 0.0; // 2D 矩形,高度设为0
|
||||
marker.points.push_back(p);
|
||||
}
|
||||
p.x = obstacle_polygons[i][0].x;
|
||||
p.y = obstacle_polygons[i][0].y;
|
||||
p.z = 0.0; // 2D 矩形,高度设为0
|
||||
marker.points.push_back(p);
|
||||
|
||||
marker_array.markers.push_back(marker);
|
||||
}
|
||||
|
||||
pub_3dbox_.publish(marker_array);
|
||||
}
|
||||
|
||||
void callback(const sensor_msgs::ImageConstPtr &image_msg,
|
||||
const sensor_msgs::PointCloud2ConstPtr &point_cloud_msg) {
|
||||
@ -499,33 +556,59 @@ public:
|
||||
}
|
||||
SendLidar(lidar_pub2_, combined_lidar_points2);
|
||||
|
||||
gDebugWarn() << G_FILE_LINE;
|
||||
// 把点云提取出3dbox
|
||||
static int obb_omp_threads = yaml_config["obb_omp_threads"].as<int>();
|
||||
// omp_set_num_threads(obb_omp_threads);
|
||||
// #pragma omp parallel for
|
||||
for (int i = 0; i < box3ds.size(); i++) {
|
||||
auto &box = box3ds[i];
|
||||
ExtractObstacles(box.lidar_cluster, box.obstacle_centroids,
|
||||
box.obstacle_sizes, box.obstacle_orientations, true);
|
||||
}
|
||||
// 暂时不需要3dbox
|
||||
// gDebugWarn() << G_FILE_LINE;
|
||||
// // 把点云提取出3dbox
|
||||
// static int obb_omp_threads = yaml_config["obb_omp_threads"].as<int>();
|
||||
// // omp_set_num_threads(obb_omp_threads);
|
||||
// // #pragma omp parallel for
|
||||
// for (int i = 0; i < box3ds.size(); i++) {
|
||||
// auto &box = box3ds[i];
|
||||
// ExtractObstacles(box.lidar_cluster, box.obstacle_centroids,
|
||||
// box.obstacle_sizes, box.obstacle_orientations, true);
|
||||
// }
|
||||
// gDebugWarn() << G_FILE_LINE;
|
||||
// std::vector<Eigen::Vector3f> obstacle_centroids;
|
||||
// std::vector<Eigen::Vector3f> obstacle_sizes;
|
||||
// std::vector<Eigen::Quaternionf> obstacle_orientations;
|
||||
// for (int i = 0; i < box3ds.size(); i++) {
|
||||
// auto &box = box3ds[i];
|
||||
// // 如果聚类失败了(点太少或者不满足要求)
|
||||
// if (box.lidar_cluster->points.empty()) {
|
||||
// continue;
|
||||
// }
|
||||
// obstacle_centroids.push_back(box.obstacle_centroids);
|
||||
// obstacle_sizes.push_back(box.obstacle_sizes);
|
||||
// obstacle_orientations.push_back(box.obstacle_orientations);
|
||||
// }
|
||||
// gDebugWarn() << G_FILE_LINE;
|
||||
// PublishObstacles(obstacle_centroids, obstacle_sizes,
|
||||
// obstacle_orientations);
|
||||
|
||||
gDebugWarn() << G_FILE_LINE;
|
||||
std::vector<Eigen::Vector3f> obstacle_centroids;
|
||||
std::vector<Eigen::Vector3f> obstacle_sizes;
|
||||
std::vector<Eigen::Quaternionf> obstacle_orientations;
|
||||
// 先把点云转到车体坐标系
|
||||
for (int i = 0; i < box3ds.size(); i++) {
|
||||
auto &box = box3ds[i];
|
||||
pcl::transformPointCloud(*box.lidar_cluster, *box.lidar_cluster,
|
||||
help.convert_lidar2car_affine_);
|
||||
// 如果聚类失败了(点太少或者不满足要求)
|
||||
if (box.lidar_cluster->points.empty()) {
|
||||
continue;
|
||||
}
|
||||
obstacle_centroids.push_back(box.obstacle_centroids);
|
||||
obstacle_sizes.push_back(box.obstacle_sizes);
|
||||
obstacle_orientations.push_back(box.obstacle_orientations);
|
||||
box.position = GetMinAreaRectInfoFrom3DCloud(box.lidar_cluster);
|
||||
// // 输出最小包围矩形的信息
|
||||
// std::cout << "Center: (" << rect.center.x << ", " << rect.center.y <<
|
||||
// ")"
|
||||
// << std::endl;
|
||||
// std::cout << "Size: (" << rect.size.width << ", " << rect.size.height
|
||||
// << ")" << std::endl;
|
||||
// std::cout << "Angle: " << rect.angle << " degrees" << std::endl;
|
||||
}
|
||||
gDebugWarn() << G_FILE_LINE;
|
||||
PublishObstacles(obstacle_centroids, obstacle_sizes, obstacle_orientations);
|
||||
auto obstacles_msg = PackageMessage(box3ds, true);
|
||||
pub_obstacles_.publish(obstacles_msg);
|
||||
|
||||
// 发布可视化内容
|
||||
auto packages_marker = Package2dBoxMarker(box3ds);
|
||||
Publish2dObstacles(packages_marker);
|
||||
}
|
||||
|
||||
void Init() {
|
||||
@ -597,6 +680,7 @@ private:
|
||||
ros::Subscriber sub_detect_congest_enable_;
|
||||
bool enable_detect_congest = true;
|
||||
ros::Publisher person_density_pub_;
|
||||
ros::Publisher pub_obstacles_;
|
||||
|
||||
ros::Publisher image_pub_;
|
||||
ros::Publisher lidar_pub1_;
|
||||
|
@ -18,6 +18,8 @@ person_distance : 5
|
||||
detect_congest_enable_topic : "/detect_congest_enable"
|
||||
# 发布的电梯拥挤度话题
|
||||
person_density_topic : "/person_density"
|
||||
# 发布的障碍物信息话题
|
||||
obstacles_topic_ : "/obstacles"
|
||||
|
||||
# 设置传感器时间同步最大时间间隔 单位s
|
||||
max_time_interval : 0.2
|
||||
|
211
src/perception_msgs/CMakeLists.txt
Normal file
211
src/perception_msgs/CMakeLists.txt
Normal file
@ -0,0 +1,211 @@
|
||||
cmake_minimum_required(VERSION 3.0.2)
|
||||
project(perception_msgs)
|
||||
|
||||
## 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
|
||||
geometry_msgs
|
||||
message_generation
|
||||
roscpp
|
||||
rospy
|
||||
std_msgs
|
||||
)
|
||||
|
||||
## 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
|
||||
# Message1.msg
|
||||
PerceptionObstacle.msg
|
||||
PerceptionObstacles.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
|
||||
geometry_msgs
|
||||
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 perception_msgs
|
||||
CATKIN_DEPENDS geometry_msgs message_generation roscpp rospy std_msgs
|
||||
# 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(${PROJECT_NAME}
|
||||
# src/${PROJECT_NAME}/perception_msgs.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(${PROJECT_NAME} ${${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(${PROJECT_NAME}_node src/perception_msgs_node.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(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
|
||||
## Specify libraries to link a library or executable target against
|
||||
# target_link_libraries(${PROJECT_NAME}_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
|
||||
# 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_perception_msgs.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)
|
3
src/perception_msgs/msg/PerceptionObstacle.msg
Normal file
3
src/perception_msgs/msg/PerceptionObstacle.msg
Normal file
@ -0,0 +1,3 @@
|
||||
string label
|
||||
geometry_msgs/Point center_point
|
||||
geometry_msgs/Point[] corner_points
|
2
src/perception_msgs/msg/PerceptionObstacles.msg
Normal file
2
src/perception_msgs/msg/PerceptionObstacles.msg
Normal file
@ -0,0 +1,2 @@
|
||||
std_msgs/Header header
|
||||
perception_msgs/PerceptionObstacle[] obstacles
|
75
src/perception_msgs/package.xml
Normal file
75
src/perception_msgs/package.xml
Normal file
@ -0,0 +1,75 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>perception_msgs</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The perception_msgs package</description>
|
||||
|
||||
<!-- One maintainer tag required, multiple allowed, one person per tag -->
|
||||
<!-- Example: -->
|
||||
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
|
||||
<maintainer email="gxt_kt@todo.todo">gxt_kt</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/perception_msgs</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>geometry_msgs</build_depend>
|
||||
<build_depend>message_generation</build_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>message_generation</build_export_depend>
|
||||
<exec_depend>message_runtime</exec_depend>
|
||||
<build_export_depend>geometry_msgs</build_export_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>geometry_msgs</exec_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
<exec_depend>rospy</exec_depend>
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
|
||||
|
||||
<!-- The export tag contains other, unspecified, tags -->
|
||||
<export>
|
||||
<!-- Other tools can request additional information be placed here -->
|
||||
|
||||
</export>
|
||||
</package>
|
Loading…
Reference in New Issue
Block a user