diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index 0a64444..623a9f9 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -2,8 +2,8 @@ name: CI on: push: - branches: - - master +# branches: +# - master pull_request: branches: - master @@ -14,24 +14,12 @@ jobs: fail-fast: false matrix: env: - - {CI_NAME: xenial, - OS_NAME: ubuntu, - OS_CODE_NAME: xenial, - ROS_DISTRO: kinetic, - ROS_REPO: main, - DOCKER_IMAGE: "ros:kinetic"} - - {CI_NAME: bionic, - OS_NAME: ubuntu, - OS_CODE_NAME: bionic, - ROS_DISTRO: melodic, - ROS_REPO: main, - DOCKER_IMAGE: "ros:melodic"} - {CI_NAME: focal, OS_NAME: ubuntu, OS_CODE_NAME: focal, - ROS_DISTRO: noetic, + ROS_DISTRO: foxy, ROS_REPO: main, - DOCKER_IMAGE: "ros:noetic"} + DOCKER_IMAGE: "ros:foxy"} runs-on: ubuntu-latest steps: - uses: actions/checkout@v2 diff --git a/CMakeLists.txt b/CMakeLists.txt index 558def9..af4ec54 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -5,33 +5,15 @@ set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_EXTENSIONS OFF) -find_package(catkin REQUIRED COMPONENTS - rviz - pluginlib - pcl_ros -) +cmake_policy(SET CMP0057 NEW) +find_package(ament_cmake REQUIRED) find_package(Eigen3 REQUIRED) - -catkin_package( - INCLUDE_DIRS - include - LIBRARIES - tool_cursor - CATKIN_DEPENDS - rviz - pluginlib - pcl_ros -) - -########### -## Build ## -########### - -include_directories( - include - ${catkin_INCLUDE_DIRS} -) +find_package(PCL REQUIRED COMPONENTS common io geometry) +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rviz_common REQUIRED) +find_package(rviz_rendering REQUIRED) # QT find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets) @@ -42,42 +24,65 @@ qt5_wrap_cpp(MOC_FILES src/mesh_tool_cursor.h ) -add_library(tool_cursor +add_library(${PROJECT_NAME} SHARED src/${PROJECT_NAME}/rviz_tool_cursor.cpp + src/${PROJECT_NAME}/get_point_on_plane.cpp src/circle_tool_cursor.cpp src/mesh_tool_cursor.cpp ${MOC_FILES} ) -target_link_libraries(tool_cursor - ${catkin_LIBRARIES} +target_link_libraries(${PROJECT_NAME} Qt5::Widgets -) + ${rclcpp_LIBRARIES} + ${rviz_common_LIBRARIES} + ${rviz_rendering_LIBRARIES} + ${pluginlib_LIBRARIES} + Eigen3::Eigen + ${PCL_LIBRARIES}) +target_include_directories(${PROJECT_NAME} + PUBLIC $ + PUBLIC $) +target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC + ${PCL_INCLUDE_DIRS}) +target_include_directories(${PROJECT_NAME} PUBLIC + ${pluginlib_INCLUDE_DIRS} + ${rviz_common_INCLUDE_DIRS} + ${rviz_rendering_INCLUDE_DIRS} + + ) +target_compile_definitions(${PROJECT_NAME} PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY") +target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") -############# -## Install ## -############# +pluginlib_export_plugin_description_file(rviz_common plugin_description.xml) # Mark executables and/or libraries for installation -install(TARGETS tool_cursor - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +install(TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + INCLUDES DESTINATION include ) # Mark cpp header files for installation -install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +install(DIRECTORY include/ + DESTINATION include ) # Mark other files for installation (e.g. launch and bag files, etc.) install(FILES plugin_description.xml - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + DESTINATION share/${PROJECT_NAME} ) install(DIRECTORY resources - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + DESTINATION share/${PROJECT_NAME} ) -############# -## Testing ## -############# +ament_export_include_directories(include) +ament_export_targets(${PROJECT_NAME} HAS_LIBRARY_TARGET) +ament_export_dependencies(${PROJECT_NAME} + rclcpp + rviz_common + rviz_rendering + pluginlib) +ament_package() diff --git a/include/rviz_tool_cursor/get_point_on_plane.hpp b/include/rviz_tool_cursor/get_point_on_plane.hpp new file mode 100644 index 0000000..08d4c3b --- /dev/null +++ b/include/rviz_tool_cursor/get_point_on_plane.hpp @@ -0,0 +1,16 @@ +#pragma once + +#include + +namespace rviz_rendering +{ +/** @brief Given a viewport and an x,y position in window-pixel coordinates, + * find the point on a plane directly behind it, if any. + * @return true if the intersection exists, false if it does not. */ +bool getPointOnPlaneFromWindowXY(Ogre::Viewport* viewport, + Ogre::Plane& plane, + int window_x, + int window_y, + Ogre::Vector3& intersection_out); + +} diff --git a/include/rviz_tool_cursor/rviz_tool_cursor.h b/include/rviz_tool_cursor/rviz_tool_cursor.h index 642c163..6be2c6a 100644 --- a/include/rviz_tool_cursor/rviz_tool_cursor.h +++ b/include/rviz_tool_cursor/rviz_tool_cursor.h @@ -1,9 +1,9 @@ -#ifndef RVIZ_TOOL_CURSOR_RVIZ_TOOL_CURSOR_H -#define RVIZ_TOOL_CURSOR_RVIZ_TOOL_CURSOR_H +#pragma once -#include -#include -#include +#include +#include +#include +#include namespace Ogre { @@ -11,17 +11,26 @@ namespace Ogre class MovableObject; } -namespace rviz +namespace rviz_common +{ + class RenderPanel; +} + +namespace rviz_common +{ +namespace properties { class StringProperty; class IntProperty; class ColorProperty; + class FloatProperty; +} } namespace rviz_tool_cursor { -class ToolCursor : public rviz::Tool +class ToolCursor : public rviz_common::Tool { Q_OBJECT public: @@ -36,7 +45,7 @@ Q_OBJECT virtual void deactivate() override; - virtual int processMouseEvent(rviz::ViewportMouseEvent& event) override; + virtual int processMouseEvent(rviz_common::ViewportMouseEvent& event) override; public Q_SLOTS: @@ -58,17 +67,15 @@ public Q_SLOTS: Ogre::MovableObject* movable_obj_; - ros::NodeHandle nh_; + rclcpp::Clock::SharedPtr clock_; - ros::Publisher pub_; + rclcpp::Publisher::SharedPtr pub_; - rviz::StringProperty* topic_property_; + rviz_common::properties::StringProperty* topic_property_; - rviz::IntProperty* patch_size_property_; + rviz_common::properties::IntProperty* patch_size_property_; - rviz::ColorProperty* color_property_; + rviz_common::properties::ColorProperty* color_property_; }; } // namespace rviz_tool_cursor - -#endif // RVIZ_TOOL_CURSOR_RVIZ_TOOL_CURSOR_H diff --git a/package.xml b/package.xml index 2485ece..1938dac 100644 --- a/package.xml +++ b/package.xml @@ -9,12 +9,13 @@ Apache 2.0 - catkin - rviz + ament_cmake + libpcl-all-dev pluginlib - pcl_ros + rviz_common + rviz_rendering - + ament_cmake diff --git a/plugin_description.xml b/plugin_description.xml index c1f2fa1..4922587 100644 --- a/plugin_description.xml +++ b/plugin_description.xml @@ -1,11 +1,11 @@ - - + + A cursor representing a circular tool that follows the geometry of mesh surfaces - + A cursor representing an input mesh that follows the geometry of mesh surfaces diff --git a/resources/default_10cm.stl b/resources/default_10cm.stl new file mode 100644 index 0000000..acf282d Binary files /dev/null and b/resources/default_10cm.stl differ diff --git a/src/circle_tool_cursor.cpp b/src/circle_tool_cursor.cpp index 7e8d20e..419918d 100644 --- a/src/circle_tool_cursor.cpp +++ b/src/circle_tool_cursor.cpp @@ -1,11 +1,12 @@ #include #include #include +#include #include -#include -#include +#include +#include #include "circle_tool_cursor.h" @@ -17,7 +18,7 @@ namespace rviz_tool_cursor CircleToolCursor::CircleToolCursor() : ToolCursor() { - radius_property_ = new rviz::FloatProperty("Tool Radius", 0.210f, + radius_property_ = new rviz_common::properties::FloatProperty("Tool Radius", 0.210f, "The radius of the tool circle display", getPropertyContainer(), SLOT(updateToolVisualization()), this); } @@ -77,4 +78,4 @@ void CircleToolCursor::updateToolVisualization() } // namespace rviz_tool_cursor -PLUGINLIB_EXPORT_CLASS(rviz_tool_cursor::CircleToolCursor, rviz::Tool) +PLUGINLIB_EXPORT_CLASS(rviz_tool_cursor::CircleToolCursor, rviz_common::Tool) diff --git a/src/circle_tool_cursor.h b/src/circle_tool_cursor.h index f75761b..c583e3c 100644 --- a/src/circle_tool_cursor.h +++ b/src/circle_tool_cursor.h @@ -1,13 +1,7 @@ -#ifndef RVIZ_TOOL_CURSOR_CIRCLE_TOOL_CURSOR_H -#define RVIZ_TOOL_CURSOR_CIRCLE_TOOL_CURSOR_H +#pragma once #include -namespace rviz -{ - class FloatProperty; -} - namespace Ogre { class ManualObject; @@ -33,11 +27,9 @@ public Q_SLOTS: virtual Ogre::MovableObject* createToolVisualization() override; - rviz::FloatProperty* radius_property_; + rviz_common::properties::FloatProperty* radius_property_; const std::string object_name_ = "circle_tool_cursor"; }; } // namespace rviz_tool_cursor - -#endif // RVIZ_TOOL_CURSOR_CIRCLE_TOOL_CURSOR_H diff --git a/src/mesh_tool_cursor.cpp b/src/mesh_tool_cursor.cpp index f918c1c..c318741 100644 --- a/src/mesh_tool_cursor.cpp +++ b/src/mesh_tool_cursor.cpp @@ -1,16 +1,19 @@ #include #include +#include #include #include #include +#include +#include #include #include "mesh_tool_cursor.h" -#include -#include +#include +#include -#include +#include const static std::string COLOR_NAME = "mesh_cursor_tool_color"; const static std::string DEFAULT_MESH_RESOURCE = "package://rviz_tool_cursor/resources/default.stl"; @@ -20,11 +23,11 @@ namespace rviz_tool_cursor MeshToolCursor::MeshToolCursor() { - mesh_file_ = new rviz::StringProperty("Mesh Filename", QString(DEFAULT_MESH_RESOURCE.c_str()), + mesh_file_ = new rviz_common::properties::StringProperty("Mesh Filename", QString(DEFAULT_MESH_RESOURCE.c_str()), "The mesh resource to display as a cursor", getPropertyContainer(), SLOT(updateToolVisualization()), this); - material_ = Ogre::MaterialManager::getSingletonPtr()->create(COLOR_NAME, "rviz"); + material_ = Ogre::MaterialManager::getSingletonPtr()->create(COLOR_NAME, "rviz_rendering"); const Ogre::ColourValue& color = color_property_->getOgreColor(); material_->getTechnique(0)->getPass(0)->setDiffuse(color.r, color.g, color.b, 1.0); @@ -39,19 +42,19 @@ MeshToolCursor::~MeshToolCursor() scene_manager_->destroyEntity(object_name_); scene_manager_->destroySceneNode(cursor_node_); } - Ogre::MaterialManager::getSingletonPtr()->remove(COLOR_NAME); + Ogre::MaterialManager::getSingletonPtr()->remove(COLOR_NAME, "rviz_rendering"); } Ogre::MovableObject* MeshToolCursor::createToolVisualization() { // Attempt to load the mesh - Ogre::MeshPtr mesh = rviz::loadMeshFromResource(mesh_file_->getStdString()); + Ogre::MeshPtr mesh = rviz_rendering::loadMeshFromResource(mesh_file_->getStdString()); if(mesh.isNull()) { - ROS_WARN("Loading default mesh..."); +// ROS_WARN("Loading default mesh..."); // Load a default mesh - mesh = rviz::loadMeshFromResource(DEFAULT_MESH_RESOURCE); + mesh = rviz_rendering::loadMeshFromResource(DEFAULT_MESH_RESOURCE); } Ogre::Entity* entity = scene_manager_->createEntity(object_name_, mesh); @@ -83,4 +86,4 @@ void MeshToolCursor::updateToolVisualization() } // namespace rviz_tool_cursor -PLUGINLIB_EXPORT_CLASS(rviz_tool_cursor::MeshToolCursor, rviz::Tool) +PLUGINLIB_EXPORT_CLASS(rviz_tool_cursor::MeshToolCursor, rviz_common::Tool) diff --git a/src/mesh_tool_cursor.h b/src/mesh_tool_cursor.h index be9ec6e..cd3358f 100644 --- a/src/mesh_tool_cursor.h +++ b/src/mesh_tool_cursor.h @@ -1,12 +1,11 @@ -#ifndef MESH_TOOL_CURSOR_H -#define MESH_TOOL_CURSOR_H - +#pragma once #include #include namespace Ogre { class Entity; + class MovableObject; } namespace rviz_tool_cursor @@ -29,7 +28,7 @@ public Q_SLOTS: virtual Ogre::MovableObject* createToolVisualization() override; - rviz::StringProperty* mesh_file_; + rviz_common::properties::StringProperty* mesh_file_; const std::string object_name_ = "mesh_tool_cursor"; @@ -37,5 +36,3 @@ public Q_SLOTS: }; } // namespace rviz_tool_cursor - -#endif // MESH_TOOL_CURSOR_H diff --git a/src/rviz_tool_cursor/get_point_on_plane.cpp b/src/rviz_tool_cursor/get_point_on_plane.cpp new file mode 100644 index 0000000..5c873c9 --- /dev/null +++ b/src/rviz_tool_cursor/get_point_on_plane.cpp @@ -0,0 +1,34 @@ +#include +#include +#include +#include +#include + +#include "rviz_tool_cursor/get_point_on_plane.hpp" + +namespace rviz_rendering +{ +/** Given a viewport and an x,y position in window-pixel coordinates, + * find the point on a plane directly behind it, if any. + * @return true if the intersection exists, false if it does not. */ +bool getPointOnPlaneFromWindowXY(Ogre::Viewport* viewport, + Ogre::Plane& plane, + int window_x, + int window_y, + Ogre::Vector3& intersection_out) +{ + int width = viewport->getActualWidth(); + int height = viewport->getActualHeight(); + + Ogre::Ray mouse_ray = viewport->getCamera()->getCameraToViewportRay((float)window_x / (float)width, + (float)window_y / (float)height); + std::pair intersection = mouse_ray.intersects(plane); + if (!intersection.first) + { + return false; + } + intersection_out = mouse_ray.getPoint(intersection.second); + + return true; +} +} // namespace rviz_rendering diff --git a/src/rviz_tool_cursor/rviz_tool_cursor.cpp b/src/rviz_tool_cursor/rviz_tool_cursor.cpp index c191e90..97c2613 100644 --- a/src/rviz_tool_cursor/rviz_tool_cursor.cpp +++ b/src/rviz_tool_cursor/rviz_tool_cursor.cpp @@ -1,19 +1,27 @@ -#include - +#include #include #include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include -#include -#include -#include -#include -#include +#include +#include -#include -#include -#include #include +#include #include @@ -52,6 +60,8 @@ Eigen::Matrix3f createMatrix(const Eigen::Vector3f& norm) Ogre::Quaternion estimateNormal(const std::vector& points, const Ogre::Vector3& camera_norm) { + (void) camera_norm; + pcl::PointCloud::Ptr cloud (new pcl::PointCloud ()); for(std::size_t i = 0; i < points.size(); ++i) @@ -68,18 +78,26 @@ Ogre::Quaternion estimateNormal(const std::vector& points, pcl::PCA pca; pca.setInputCloud(cloud); Eigen::Matrix3f& evecs = pca.getEigenVectors(); + Eigen::Vector3f& evalues = pca.getEigenValues(); // Get the eigenvector associated with the smallest eigenvalue // (should be Z-axis, assuming points are relatively planar) Eigen::Vector3f norm = evecs.col(2); norm.normalize(); - // The - Eigen::Vector3f camera_normal; - camera_normal << camera_norm.x, camera_norm.y, camera_norm.z; - camera_normal.normalize(); + // Alternate camera-relative normal vector check that doesn't require the camera vector: + // The patch points begin at the top left corner of the patch and end at the bottom right corner. + // The vector that goes between these points will point down and to the right relative to the RViz camera frame. + pcl::PointXYZ first_pt = cloud->front(); + pcl::PointXYZ last_pt = cloud->back(); + Eigen::Vector3f patch_span(last_pt.x - first_pt.x, last_pt.y - first_pt.y, last_pt.z - first_pt.z); + + // This vector (most of the time) points at least a little bit to the right, so its cross product with UnitZ + // will have a component pointing out of the screen. + Eigen::Vector3f out_vec = patch_span.cross(Eigen::Vector3f::UnitZ()); - if(norm.dot(camera_normal) < 0) + // Determine if the norm is pointing into the surface relative to the camera. If not, reverse it. + if(norm.dot(out_vec) > 0) { norm *= -1; } @@ -103,24 +121,22 @@ namespace rviz_tool_cursor { ToolCursor::ToolCursor() - : rviz::Tool() + : rviz_common::Tool() { shortcut_key_ = 'c'; - topic_property_ = new rviz::StringProperty("Topic", "/selection_point", + topic_property_ = new rviz_common::properties::StringProperty("Topic", "/selection_point", "The topic on which to publish points", getPropertyContainer(), SLOT(updateTopic()), this); - patch_size_property_ = new rviz::IntProperty("Patch Size", 10, + patch_size_property_ = new rviz_common::properties::IntProperty("Patch Size", 10, "The number of pixels with which to estimate the surface normal", getPropertyContainer()); - color_property_ = new rviz::ColorProperty("Color", QColor(255, 255, 255), + color_property_ = new rviz_common::properties::ColorProperty("Color", QColor(255, 255, 255), "The color of the tool visualization", getPropertyContainer(), SLOT(updateToolVisualization()), this); - - updateTopic(); } ToolCursor::~ToolCursor() @@ -142,7 +158,9 @@ void ToolCursor::onInitialize() // Set the cursors hit_cursor_ = cursor_; - std_cursor_ = rviz::getDefaultCursor(); + std_cursor_ = rviz_common::getDefaultCursor(); + + updateTopic(); } void ToolCursor::activate() @@ -157,10 +175,12 @@ void ToolCursor::deactivate() void ToolCursor::updateTopic() { - pub_ = nh_.advertise(topic_property_->getStdString(), 1, true); + rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node(); + pub_ = raw_node->template create_publisher(topic_property_->getStdString(), rclcpp::QoS(1)); + clock_ = raw_node->get_clock(); } -int ToolCursor::processMouseEvent(rviz::ViewportMouseEvent& event) +int ToolCursor::processMouseEvent(rviz_common::ViewportMouseEvent& event) { // Get the 3D point in space indicated by the mouse and a patch of points around it // with which to estimate the surface normal @@ -172,8 +192,10 @@ int ToolCursor::processMouseEvent(rviz::ViewportMouseEvent& event) // Set the visibility of this node off so the selection manager won't choose a point on our cursor mesh in the point and patch cursor_node_->setVisible(false); - bool got_point = context_->getSelectionManager()->get3DPoint(event.viewport, event.x, event.y, position); - bool got_patch = context_->getSelectionManager()->get3DPatch(event.viewport, event.x, event.y, patch_size, patch_size, true, points); + bool got_point = context_->getViewPicker()->get3DPoint(event.panel, event.x, event.y, position); + + // TODO: move to public API (private member function) + bool got_patch = context_->getViewPicker()->get3DPatch(event.panel, event.x, event.y, patch_size, patch_size, true, points); // Revisualize the cursor node cursor_node_->setVisible(true); @@ -181,45 +203,45 @@ int ToolCursor::processMouseEvent(rviz::ViewportMouseEvent& event) if(got_point && got_patch && points.size() > 3) { // Set the cursor - rviz::Tool::setCursor(hit_cursor_); + rviz_common::Tool::setCursor(hit_cursor_); // Estimate the surface normal from the patch of points - Ogre::Quaternion q = estimateNormal(points, event.viewport->getCamera()->getDirection()); + Ogre::Quaternion q = estimateNormal(points, rviz_rendering::RenderWindowOgreAdapter::getOgreViewport(event.panel->getRenderWindow())->getCamera()->getDirection()); cursor_node_->setOrientation(q); cursor_node_->setPosition(position); if(event.leftUp()) { // Publish a point message upon release of the left mouse button - geometry_msgs::PoseStamped msg; - msg.header.frame_id = context_->getFixedFrame().toStdString(); - msg.header.stamp = ros::Time::now(); + auto msg = std::make_unique(); + msg->header.frame_id = context_->getFixedFrame().toStdString(); + msg->header.stamp = clock_->now(); - msg.pose.position.x = static_cast(position.x); - msg.pose.position.y = static_cast(position.y); - msg.pose.position.z = static_cast(position.z); + msg->pose.position.x = static_cast(position.x); + msg->pose.position.y = static_cast(position.y); + msg->pose.position.z = static_cast(position.z); - msg.pose.orientation.w = static_cast(q.w); - msg.pose.orientation.x = static_cast(q.x); - msg.pose.orientation.y = static_cast(q.y); - msg.pose.orientation.z = static_cast(q.z); + msg->pose.orientation.w = static_cast(q.w); + msg->pose.orientation.x = static_cast(q.x); + msg->pose.orientation.y = static_cast(q.y); + msg->pose.orientation.z = static_cast(q.z); - pub_.publish(msg); + pub_->publish(std::move(msg)); } } else { // Set the standard cursor - rviz::Tool::setCursor(std_cursor_); + rviz_common::Tool::setCursor(std_cursor_); // Project the tool visualization onto the ground Ogre::Plane plane (Ogre::Vector3::UNIT_Z, 0.0f); - rviz::getPointOnPlaneFromWindowXY(event.viewport, plane, event.x, event.y, position); + rviz_rendering::getPointOnPlaneFromWindowXY(rviz_rendering::RenderWindowOgreAdapter::getOgreViewport(event.panel->getRenderWindow()), plane, event.x, event.y, position); cursor_node_->setOrientation(1.0f, 0.0f, 0.0f, 0.0f); cursor_node_->setPosition(position); } - return rviz::Tool::Render; + return rviz_common::Tool::Render; } } // namespace rviz_tool_cursor