Lenotary il y a 2 ans
commit
1f135fb7fe
4 fichiers modifiés avec 506 ajouts et 0 suppressions
  1. 217 0
      CMakeLists.txt
  2. 6 0
      launch/run.launch
  3. 74 0
      package.xml
  4. 209 0
      src/generate_map.cpp

+ 217 - 0
CMakeLists.txt

@@ -0,0 +1,217 @@
+cmake_minimum_required(VERSION 3.0.2)
+project(map_generate)
+
+# 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
+        sensor_msgs
+        std_msgs
+        tf
+        pcl_conversions
+        pcl_ros
+        )
+find_package(PCL REQUIRED QUIET)
+find_package(cmake_modules REQUIRED)
+find_package(Eigen3 REQUIRED)
+include_directories(${EIGEN3_INCLUDE_DIR})
+add_definitions(${EIGEN_DEFINITIONS})
+
+## 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
+#   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
+#   sensor_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 map_generate
+        #  CATKIN_DEPENDS roscpp rospy sensor_msgs std_msg tf
+        #  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}/map_generate.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/generate_map.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}
+        ${PCL_LIBRARIES}
+        /usr/local/lib/liblas.so.3
+        )
+
+#############
+## 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_map_generate.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)

+ 6 - 0
launch/run.launch

@@ -0,0 +1,6 @@
+<launch>
+    <node pkg="map_generate" type="node" name="map_generate_node" output="screen">
+    </node>
+    <include file="$(find motor_control)/launch/run.launch"/>
+    <include file="$(find livox_ros_driver)/launch/livox_lidar.launch"/>
+</launch>

+ 74 - 0
package.xml

@@ -0,0 +1,74 @@
+<?xml version="1.0"?>
+<package format="2">
+  <name>map_generate</name>
+  <version>0.0.0</version>
+  <description>The map_generate package</description>
+
+  <!-- One maintainer tag required, multiple allowed, one person per tag -->
+  <!-- Example:  -->
+  <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
+  <maintainer email="lenotary@todo.todo">lenotary</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/map_generate</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>sensor_msgs</build_depend>
+  <build_depend>std_msgs</build_depend>
+  <build_depend>tf</build_depend>
+  <build_export_depend>roscpp</build_export_depend>
+  <build_export_depend>rospy</build_export_depend>
+  <build_export_depend>sensor_msgs</build_export_depend>
+  <build_export_depend>std_msgS</build_export_depend>
+  <build_export_depend>tf</build_export_depend>
+  <exec_depend>roscpp</exec_depend>
+  <exec_depend>rospy</exec_depend>
+  <exec_depend>sensor_msgs</exec_depend>
+  <exec_depend>std_msgs</exec_depend>
+  <exec_depend>tf</exec_depend>
+
+
+  <!-- The export tag contains other, unspecified, tags -->
+  <export>
+    <!-- Other tools can request additional information be placed here -->
+
+  </export>
+</package>

+ 209 - 0
src/generate_map.cpp

@@ -0,0 +1,209 @@
+/**
+ * \file generate_map.cpp
+ * \brief 简要介绍
+ * \details 详细说明
+ * \author lenotary
+ * \version 1.0
+ * \date 2021/12/22
+ * \pre 先决条件。(有的话才添加。)
+ * \bug 存在的bug。(有的话才添加,注明“还未发现”也可以。)
+ * \warning 警告。(有的话才添加。)
+ * \copyright 版权声明。(通常只写遵循什么协议,版权详细内容应放在LICENSE文件中,并且应该与LICENSE文件的内容统一,不能自相矛盾。)
+ * \since 一些历史情况记录。(有的话才添加。)
+ */
+//
+// Created by lenotary on 2021/12/22.
+//
+#include <liblas/liblas.hpp>
+#include <ros/ros.h>
+#include <pcl/pcl_base.h>
+#include <pcl/point_cloud.h>
+#include <pcl_conversions/pcl_conversions.h>
+#include <pcl/point_types.h>
+#include <pcl/common/transforms.h>
+#include <tf/transform_datatypes.h>
+#include <pcl/io/io.h>
+#include <ros/ros.h>
+#include <iostream>
+#include <fstream>
+#include <sstream>    //使用stringstream需要引入这个头文件
+#include <Eigen/Eigen>
+#include <Eigen/Dense>
+#include <Eigen/Geometry>
+#include <Eigen/Eigenvalues>
+#include <fstream>
+#include <sstream>
+#include <sensor_msgs/PointCloud2.h>
+#include <sensor_msgs/Imu.h>
+#include <std_msgs/Float64.h>
+#include <std_msgs/String.h>
+#include <queue>
+#include <mutex>
+
+ros::Publisher pubResult;
+ros::Publisher pubMotorPose;
+std::queue<sensor_msgs::Imu> bufferImu;
+
+std::mutex imuMutex;
+std::mutex cloudMutex;
+
+double generateStartTime, runStartTime;
+int scanCount, runEndCount;
+bool isScan, localScanEnd, isGenerate, isRunEnd;
+sensor_msgs::Imu imuMsg;
+std_msgs::Float64 targetPose;
+pcl::PointCloud<pcl::PointXYZI>::Ptr mapCloud;
+
+pcl::PointCloud<pcl::PointXYZI>::Ptr transformPointCloud(pcl::PointCloud<pcl::PointXYZI>::Ptr cloudIn, Eigen::Affine3f transCur);
+
+void callBackImu(const sensor_msgs::Imu::ConstPtr &msg) {
+    tf::Quaternion quat;
+    tf::quaternionMsgToTF(msg->orientation, quat);
+    double roll, pitch, yaw;//定义存储r\p\y的容器
+    tf::Matrix3x3(quat).getRPY(roll, pitch, yaw);//进行转换
+    imuMsg = *msg;
+    imuMutex.lock();
+    bufferImu.push(*msg);
+    if (isScan) {
+        if (scanCount == 1 and !isGenerate and isRunEnd) {
+            targetPose.data += 0.2;
+            if (targetPose.data > M_PI) {
+                targetPose.data = M_PI;
+            }
+            isRunEnd = false;
+            runEndCount = 0;
+            runStartTime = ros::Time::now().toSec();
+            pubMotorPose.publish(targetPose);
+
+        } else if (scanCount == 2 and !isGenerate and isRunEnd) {
+            targetPose.data -= 0.2;
+            isRunEnd = false;
+            runEndCount = 0;
+
+            if (targetPose.data < -M_PI) {
+                targetPose.data = -M_PI;
+            }
+            pubMotorPose.publish(targetPose);
+            runStartTime = ros::Time::now().toSec();
+
+        } else if (scanCount == 3 and !isGenerate and isRunEnd) {
+
+            pubMotorPose.publish(targetPose);
+            targetPose.data += 0.2;
+            isRunEnd = false;
+            runEndCount = 0;
+            pubMotorPose.publish(targetPose);
+            runStartTime = ros::Time::now().toSec();
+
+        }
+        if (not isRunEnd and std::abs(targetPose.data - yaw) < 0.01) {
+            runEndCount++;
+            if (scanCount == 1 and std::abs(targetPose.data - M_PI) < 0.01) {
+                scanCount++;
+            } else if (scanCount == 2 and std::abs(targetPose.data + M_PI) < 0.01) {
+                scanCount++;
+            } else if (scanCount == 3 and targetPose.data > 0) {
+                targetPose.data = 0;
+                scanCount = 1;
+                isScan = false;
+                ROS_INFO("stop generate auto");
+            }
+            if (runEndCount > 10) {
+                isRunEnd = true;
+                isGenerate = true;
+                generateStartTime = ros::Time::now().toSec();
+//                ROS_INFO("info pose error %f time error %f",yaw- targetPose.data,ros::Time::now().toSec() - runStartTime);
+            }
+        }
+        if (ros::Time::now().toSec() - generateStartTime > 1.0) {
+            isGenerate = false;
+        }
+    }
+
+    imuMutex.unlock();
+
+
+}
+
+void callBackCloud(const sensor_msgs::PointCloud2::ConstPtr &msg) {
+
+    imuMutex.lock();
+    if (isGenerate) {
+//        double roll, pitch, yaw;//定义存储r\p\y的容器
+//        tf::Quaternion quat;
+//        tf::quaternionMsgToTF(imuMsg.orientation, quat);
+//        tf::Matrix3x3(quat).getRPY(roll, pitch, yaw);//进行转换
+//
+//        Eigen::Affine3f transform = Eigen::Affine3f::Identity();
+//        transform.rotate(Eigen::AngleAxisf(yaw, Eigen::Vector3f::UnitZ()));
+////            std::cout << transform <<std::endl;
+//        pcl::PointCloud<pcl::PointXYZI>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZI>);
+//        pcl::fromROSMsg(*msg, *cloud);
+//        *mapCloud += *transformPointCloud(cloud, transform);
+    }
+    imuMutex.unlock();
+}
+
+void callControl(const std_msgs::String::ConstPtr &msg) {
+    if (msg->data == "start") {
+        isScan = true;
+        targetPose.data = 0;
+        scanCount = 1;
+        pubMotorPose.publish(targetPose);
+        ROS_INFO("start generate");
+    } else if (msg->data == "stop") {
+        isScan = false;
+        ROS_INFO("stop generate manual");
+    }
+}
+pcl::PointCloud<pcl::PointXYZI>::Ptr transformPointCloud(pcl::PointCloud<pcl::PointXYZI>::Ptr cloudIn, Eigen::Affine3f transCur) {
+    pcl::PointCloud<pcl::PointXYZI>::Ptr cloudOut(new pcl::PointCloud<pcl::PointXYZI>());
+
+    pcl::PointXYZI *pointFrom;
+
+    int cloudSize = cloudIn->size();
+    cloudOut->resize(cloudSize);
+
+//    Eigen::Affine3f transCur = pcl::getTransformation(transformIn->x, transformIn->y, transformIn->z,
+//                                                      transformIn->roll, transformIn->pitch, transformIn->yaw);
+
+    for (int i = 0; i < cloudSize; ++i) {
+        pointFrom = &cloudIn->points[i];
+        cloudOut->points[i].x =
+                transCur(0, 0) * pointFrom->x + transCur(0, 1) * pointFrom->y + transCur(0, 2) * pointFrom->z +
+                transCur(0, 3);
+        cloudOut->points[i].y =
+                transCur(1, 0) * pointFrom->x + transCur(1, 1) * pointFrom->y + transCur(1, 2) * pointFrom->z +
+                transCur(1, 3);
+        cloudOut->points[i].z =
+                transCur(2, 0) * pointFrom->x + transCur(2, 1) * pointFrom->y + transCur(2, 2) * pointFrom->z +
+                transCur(2, 3);
+        cloudOut->points[i].intensity = pointFrom->intensity;
+    }
+    return cloudOut;
+}
+int main(int argc, char **argv) {
+    ros::init(argc, argv, "node");
+    ros::NodeHandle nh;
+    ros::NodeHandle nhPrivate("~");
+
+
+    pubResult = nh.advertise<std_msgs::String>("result", 1);
+    pubMotorPose = nh.advertise<std_msgs::Float64>("motor_set_pose", 1);
+    ros::Subscriber subImu = nh.subscribe("motor_pose_imu", 1000, &callBackImu);
+    ros::Subscriber subCloud = nh.subscribe("livox/lidar", 1, &callBackCloud);
+    ros::Subscriber subControl = nh.subscribe("generate_control", 1, &callControl);
+    mapCloud.reset(new pcl::PointCloud<pcl::PointXYZI>);
+    scanCount = 0;
+    isScan = false;
+    localScanEnd = false;
+    isGenerate = false;
+    isRunEnd = false;
+
+    while (ros::ok()) {
+
+        ros::spinOnce();
+    }
+
+    return 0;
+}