Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
79 changes: 44 additions & 35 deletions interactive_marker_tutorials/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,51 +22,60 @@ ament_export_dependencies(
"visualization_msgs")

add_executable(basic_controls src/basic_controls.cpp)
ament_target_dependencies(basic_controls
"interactive_markers"
"rclcpp"
"tf2"
"tf2_geometry_msgs"
"tf2_ros"
"visualization_msgs")
target_link_libraries(basic_controls PUBLIC
${visualization_msgs_TARGETS}
interactive_markers::interactive_markers
rclcpp::rclcpp
tf2::tf2
tf2_geometry_msgs::tf2_geometry_msgs
tf2_ros::static_transform_broadcaster_node
tf2_ros::tf2_ros
)

add_executable(cube src/cube.cpp)
ament_target_dependencies(cube
"interactive_markers"
"rclcpp"
"tf2"
"visualization_msgs")
target_link_libraries(cube PUBLIC
${visualization_msgs_TARGETS}
interactive_markers::interactive_markers
rclcpp::rclcpp
tf2::tf2
)

add_executable(selection src/selection.cpp)
ament_target_dependencies(selection
"geometry_msgs"
"interactive_markers"
"rclcpp"
"std_msgs"
"tf2"
"tf2_geometry_msgs"
"visualization_msgs")
target_link_libraries(selection PUBLIC
${geometry_msgs_TARGETS}
${std_msgs_TARGETS}
${visualization_msgs_TARGETS}
interactive_markers::interactive_markers
rclcpp::rclcpp
tf2::tf2
tf2_geometry_msgs::tf2_geometry_msgs
)

add_executable(simple_marker src/simple_marker.cpp)
ament_target_dependencies(simple_marker
"interactive_markers"
"rclcpp"
"visualization_msgs")
target_link_libraries(simple_marker PUBLIC
${visualization_msgs_TARGETS}
interactive_markers::interactive_markers
rclcpp::rclcpp
)

add_executable(menu src/menu.cpp)
ament_target_dependencies(menu
"interactive_markers"
"rclcpp"
"visualization_msgs")
target_link_libraries(menu PUBLIC
${visualization_msgs_TARGETS}
interactive_markers::interactive_markers
rclcpp::rclcpp
)


add_library(pong_library SHARED src/pong.cpp)
ament_target_dependencies(pong_library
"interactive_markers"
"rclcpp"
"rclcpp_components"
"tf2"
"tf2_geometry_msgs"
"visualization_msgs")
target_link_libraries(pong_library
${visualization_msgs_TARGETS}
interactive_markers::interactive_markers
rclcpp::rclcpp
rclcpp_components::component
rclcpp_components::component_manager
tf2::tf2
tf2_geometry_msgs::tf2_geometry_msgs
)
# Register pong plugin and build an executable
rclcpp_components_register_node(pong_library
PLUGIN "interactive_marker_tutorials::PongGameNode"
Expand Down
10 changes: 5 additions & 5 deletions interactive_marker_tutorials/src/basic_controls.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,12 +34,12 @@
#include "interactive_markers/interactive_marker_server.hpp"
#include "interactive_markers/menu_handler.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/LinearMath/Transform.h"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Vector3.h"
#include "tf2/transform_datatypes.h"
#include "tf2/LinearMath/Transform.hpp"
#include "tf2/LinearMath/Quaternion.hpp"
#include "tf2/LinearMath/Vector3.hpp"
#include "tf2/transform_datatypes.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2_ros/transform_broadcaster.h"
#include "tf2_ros/transform_broadcaster.hpp"
#include "visualization_msgs/msg/interactive_marker.hpp"
#include "visualization_msgs/msg/interactive_marker_control.hpp"
#include "visualization_msgs/msg/interactive_marker_feedback.hpp"
Expand Down
2 changes: 1 addition & 1 deletion interactive_marker_tutorials/src/cube.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include "geometry_msgs/msg/pose.hpp"
#include "interactive_markers/interactive_marker_server.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/LinearMath/Vector3.h"
#include "tf2/LinearMath/Vector3.hpp"
#include "visualization_msgs/msg/interactive_marker.hpp"
#include "visualization_msgs/msg/interactive_marker_control.hpp"
#include "visualization_msgs/msg/interactive_marker_feedback.hpp"
Expand Down
2 changes: 1 addition & 1 deletion interactive_marker_tutorials/src/pong.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#include "interactive_markers/interactive_marker_server.hpp"
#include "rclcpp/create_timer.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Quaternion.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "visualization_msgs/msg/marker.hpp"
#include "visualization_msgs/msg/interactive_marker.hpp"
Expand Down
2 changes: 1 addition & 1 deletion interactive_marker_tutorials/src/selection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
#include "interactive_markers/tools.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/color_rgba.hpp"
#include "tf2/LinearMath/Vector3.h"
#include "tf2/LinearMath/Vector3.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "visualization_msgs/msg/interactive_marker.hpp"
#include "visualization_msgs/msg/interactive_marker_control.hpp"
Expand Down
19 changes: 11 additions & 8 deletions librviz_tutorial/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,14 +34,17 @@ set(SRC_FILES
## Add the "myviz" executable and specify the list of source files we
## collected above in ``${SRC_FILES}``.
add_executable(myviz ${SRC_FILES})
ament_target_dependencies(myviz
"Qt5Core"
"Qt5Widgets"
"rclcpp"
"rviz_common"
"rviz_default_plugins"
"rviz_rendering")
target_include_directories(myviz PUBLIC
target_link_libraries(myviz PUBLIC
Qt5Core
Qt5Widgets
rclcpp::rclcpp
rviz_common::rviz_common
rviz_default_plugins::rviz_default_plugins
rviz_rendering::rviz_rendering
)


target_include_directories(myviz PUBLIC
${Qt5Widgets_INCLUDE_DIRS}
${Qt5Core_INCLUDE_DIRS})

Expand Down
19 changes: 12 additions & 7 deletions rviz_plugin_tutorials/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ find_package(geometry_msgs REQUIRED)
find_package(pluginlib REQUIRED)
find_package(Qt5 REQUIRED COMPONENTS Widgets)
find_package(rclcpp REQUIRED)
find_package(resource_retriever REQUIRED)
find_package(rviz_common REQUIRED)
find_package(rviz_rendering REQUIRED)
find_package(sensor_msgs REQUIRED)
Expand All @@ -42,14 +43,18 @@ set(SRC_FILES
## is called) and specify the list of source files we collected above
## in ``${SRC_FILES}``. We also add the needed dependencies.
add_library(${PROJECT_NAME} SHARED ${SRC_FILES})
ament_target_dependencies(${PROJECT_NAME}
"geometry_msgs"
"rclcpp"
"rviz_common"
"rviz_rendering"
"sensor_msgs")
target_link_libraries(${PROJECT_NAME}
${geometry_msgs_TARGETS}
${sensor_msgs_TARGETS}
rclcpp::rclcpp
resource_retriever::resource_retriever
rviz_common::rviz_common
rviz_rendering::rviz_rendering
sensor_msgs::sensor_msgs_library
)
target_include_directories(${PROJECT_NAME} PUBLIC
${Qt5Widgets_INCLUDE_DIRS})
${Qt5Widgets_INCLUDE_DIRS}
)

## Here we export the plugins and meshes so they can be found by RViz at runtime.
pluginlib_export_plugin_description_file(rviz_common plugin_description.xml)
Expand Down
2 changes: 1 addition & 1 deletion rviz_plugin_tutorials/src/imu_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include "rviz_common/properties/color_property.hpp"
#include "rviz_common/properties/float_property.hpp"
#include "rviz_common/properties/int_property.hpp"
#include "tf2_ros/transform_listener.h"
#include "tf2_ros/transform_listener.hpp"

#include "imu_visual.hpp"

Expand Down
2 changes: 1 addition & 1 deletion rviz_plugin_tutorials/src/plant_flag_tool.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ void PlantFlagTool::onInitialize()
{
flag_resource_ = "package://rviz_plugin_tutorials/media/flag.dae";

if (!rviz_rendering::loadMeshFromResource(flag_resource_)) {
if (!rviz_rendering::loadMeshFromResource(&this->retriever_, flag_resource_)) {
RCLCPP_ERROR(
rclcpp::get_logger("plant_flag_tool"),
"PlantFlagTool: failed to load model resource '%s'.",
Expand Down
2 changes: 2 additions & 0 deletions rviz_plugin_tutorials/src/plant_flag_tool.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#include <Ogre.h>

#include "rviz_common/tool.hpp"
#include <resource_retriever/retriever.hpp>

namespace Ogre
{
Expand Down Expand Up @@ -85,6 +86,7 @@ class PlantFlagTool : public rviz_common::Tool
Ogre::SceneNode * moving_flag_node_;
std::string flag_resource_;
rviz_common::properties::VectorProperty * current_flag_property_;
resource_retriever::Retriever retriever_;
};
// END_TUTORIAL

Expand Down
17 changes: 10 additions & 7 deletions visualization_marker_tutorials/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,15 +21,18 @@ ament_export_dependencies(
visualization_msgs)

add_executable(basic_shapes src/basic_shapes.cpp)
ament_target_dependencies(basic_shapes
"rclcpp"
"visualization_msgs")
target_link_libraries(basic_shapes PUBLIC
${visualization_msgs_TARGETS}
rclcpp::rclcpp
)

add_executable(points_and_lines src/points_and_lines.cpp)
ament_target_dependencies(points_and_lines
"rclcpp"
"geometry_msgs"
"visualization_msgs")
target_link_libraries(points_and_lines PUBLIC
${geometry_msgs_TARGETS}
${visualization_msgs_TARGETS}
rclcpp::rclcpp
)


if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
Expand Down