Skip to content

Commit

Permalink
srdf publisher node (#2682)
Browse files Browse the repository at this point in the history
  • Loading branch information
tylerjw authored Feb 13, 2024
1 parent fbad1c2 commit 74feda2
Show file tree
Hide file tree
Showing 6 changed files with 295 additions and 47 deletions.
87 changes: 49 additions & 38 deletions moveit_ros/planning/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,76 +6,82 @@ find_package(moveit_common REQUIRED)
moveit_package()

find_package(ament_cmake REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(fmt REQUIRED)
find_package(generate_parameter_library REQUIRED)
find_package(message_filters REQUIRED)
find_package(moveit_core REQUIRED)
find_package(moveit_msgs REQUIRED)
# find_package(moveit_ros_perception REQUIRED)
find_package(moveit_ros_occupancy_map_monitor REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(message_filters REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(srdfdom REQUIRED)
find_package(urdf REQUIRED)
find_package(std_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_eigen REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(moveit_core REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(moveit_ros_occupancy_map_monitor REQUIRED)
find_package(urdf REQUIRED)
# find_package(moveit_ros_perception REQUIRED)

# Finds Boost Components
include(ConfigExtras.cmake)

set(THIS_PACKAGE_INCLUDE_DIRS
rdf_loader/include
kinematics_plugin_loader/include
robot_model_loader/include
collision_plugin_loader/include
constraint_sampler_manager_loader/include
planning_pipeline/include
kinematics_plugin_loader/include
moveit_cpp/include
plan_execution/include
planning_pipeline_interfaces/include
planning_pipeline/include
planning_scene_monitor/include
trajectory_execution_manager/include
plan_execution/include
collision_plugin_loader/include
moveit_cpp/include)
rdf_loader/include
robot_model_loader/include
trajectory_execution_manager/include)

set(THIS_PACKAGE_LIBRARIES
moveit_rdf_loader
moveit_kinematics_plugin_loader
moveit_robot_model_loader
moveit_constraint_sampler_manager_loader
planning_pipeline_parameters
moveit_planning_pipeline
moveit_planning_pipeline_interfaces
moveit_trajectory_execution_manager
moveit_plan_execution
moveit_planning_scene_monitor
moveit_collision_plugin_loader
default_request_adapter_parameters
default_response_adapter_parameters
moveit_collision_plugin_loader
moveit_constraint_sampler_manager_loader
moveit_cpp
moveit_default_planning_request_adapter_plugins
moveit_default_planning_response_adapter_plugins
moveit_cpp)
moveit_kinematics_plugin_loader
moveit_plan_execution
moveit_planning_pipeline
moveit_planning_pipeline_interfaces
moveit_planning_scene_monitor
moveit_rdf_loader
moveit_robot_model_loader
moveit_trajectory_execution_manager
planning_pipeline_parameters
srdf_publisher_node)

set(THIS_PACKAGE_INCLUDE_DEPENDS
pluginlib
Eigen3
generate_parameter_library
rclcpp
message_filters
moveit_core
moveit_msgs
moveit_ros_occupancy_map_monitor
pluginlib
rclcpp
rclcpp_components
srdfdom
urdf
std_msgs
tf2
tf2_eigen
tf2_geometry_msgs
tf2_msgs
tf2_ros
Eigen3
moveit_core
urdf
# moveit_ros_perception
moveit_ros_occupancy_map_monitor
moveit_msgs
tf2_msgs
tf2_geometry_msgs)
)

include_directories(${THIS_PACKAGE_INCLUDE_DIRS})
include_directories(SYSTEM ${EIGEN3_INCLUDE_DIRS})
Expand All @@ -86,13 +92,14 @@ add_subdirectory(kinematics_plugin_loader)
add_subdirectory(moveit_cpp)
add_subdirectory(plan_execution)
add_subdirectory(planning_components_tools)
add_subdirectory(planning_pipeline)
add_subdirectory(planning_pipeline_interfaces)
add_subdirectory(planning_pipeline)
add_subdirectory(planning_request_adapter_plugins)
add_subdirectory(planning_response_adapter_plugins)
add_subdirectory(planning_scene_monitor)
add_subdirectory(rdf_loader)
add_subdirectory(robot_model_loader)
add_subdirectory(srdf_publisher_node)
add_subdirectory(trajectory_execution_manager)

install(
Expand All @@ -107,6 +114,10 @@ install(
ament_export_targets(moveit_ros_planningTargets HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})

rclcpp_components_register_node(
srdf_publisher_node PLUGIN "moveit_ros_planning::SrdfPublisher" EXECUTABLE
srdf_publisher)

pluginlib_export_plugin_description_file(
moveit_core "default_request_adapters_plugin_description.xml")
pluginlib_export_plugin_description_file(
Expand Down
17 changes: 10 additions & 7 deletions moveit_ros/planning/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,28 +24,31 @@

<buildtool_export_depend>eigen3_cmake_module</buildtool_export_depend>

<depend version_gte="1.11.2">pluginlib</depend>
<depend>ament_index_cpp</depend>
<depend>eigen</depend>
<depend>fmt</depend>
<depend>generate_parameter_library</depend>
<depend>message_filters</depend>
<depend>moveit_core</depend>
<depend>moveit_ros_occupancy_map_monitor</depend>
<depend>moveit_msgs</depend>
<depend>message_filters</depend>
<depend version_gte="1.11.2">pluginlib</depend>
<depend>moveit_ros_occupancy_map_monitor</depend>
<depend>rclcpp_action</depend>
<depend>rclcpp_components</depend>
<depend>rclcpp</depend>
<depend>srdfdom</depend>
<depend>urdf</depend>
<depend>tf2</depend>
<depend>std_msgs</depend>
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_msgs</depend>
<depend>tf2_ros</depend>
<depend>eigen</depend>
<depend>fmt</depend>
<depend>tf2</depend>
<depend>urdf</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ros_testing</test_depend>
<test_depend>launch_testing_ament_cmake</test_depend>

<test_depend>moveit_resources_panda_moveit_config</test_depend>

Expand Down
4 changes: 2 additions & 2 deletions moveit_ros/planning/planning_components_tools/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# NOTE: For some reason ament_lint_cmake [linelength] only complains about this
# file
# NOTE: For some reason ament_lint_cmake [linelength] only caware omplains about
# this file
# TODO(henningkayser): Disable linelength filter once number of digits is
# configurable - set to 120 lint_cmake: -linelength
add_executable(moveit_print_planning_model_info
Expand Down
9 changes: 9 additions & 0 deletions moveit_ros/planning/srdf_publisher_node/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
add_library(srdf_publisher_node SHARED src/srdf_publisher_node.cpp)
ament_target_dependencies(srdf_publisher_node PUBLIC std_msgs rclcpp
rclcpp_components)

if(BUILD_TESTING)
find_package(launch_testing_ament_cmake REQUIRED)

add_launch_test(test/srdf_publisher_test.py TARGET test-srdf_publisher)
endif()
101 changes: 101 additions & 0 deletions moveit_ros/planning/srdf_publisher_node/src/srdf_publisher_node.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,101 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2024, PickNik Robotics Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of PickNik Robotics Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

// SrdfPublisher Node
// Author: Tyler Weaver
//
// Node with a single parameter and single publisher using transient local QoS.
// Publishes string set on parameter `robot_description_semantic` to topic
// `/robot_description_semantic`.
//
// This is similar to what [robot_state_publisher](https://github.com/ros/robot_state_publisher)
// does for the URDF using parameter `robot_description` and topic `/robot_description`.
//
// As MoveIt subscribes to the topic `/robot_description_semantic` for the srdf
// this node can be used when you want to set the SRDF parameter on only one node
// and have the rest of your system use a subscriber to that topic to get the
// SRDF.

#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>

#include <string>

namespace moveit_ros_planning
{

class SrdfPublisher : public rclcpp::Node
{
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr srdf_publisher_;
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_handle_;

public:
SrdfPublisher(const rclcpp::NodeOptions& options) : rclcpp::Node("srdf_publisher", options)
{
srdf_publisher_ = this->create_publisher<std_msgs::msg::String>("robot_description_semantic",
rclcpp::QoS(1).transient_local().reliable());

// TODO: Update the callback used here once Humble is EOL
// Using add_on_set_parameters_callback as it is the only parameter callback available in Humble.
// This is also why we have to return an always success validation.
// Once Humble is EOL use add_post_set_parameters_callback.
on_set_parameters_handle_ =
this->add_on_set_parameters_callback([this](const std::vector<rclcpp::Parameter>& parameters) {
for (auto const& parameter : parameters)
{
if (parameter.get_name() == "robot_description_semantic")
{
std_msgs::msg::String msg;
msg.data = parameter.get_value<std::string>();
srdf_publisher_->publish(msg);
break;
}
}

rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
return result;
});

rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING;
descriptor.description = "Semantic Robot Description Format";
this->declare_parameter("robot_description_semantic", rclcpp::ParameterType::PARAMETER_STRING, descriptor);
}
};

} // namespace moveit_ros_planning

#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(moveit_ros_planning::SrdfPublisher)
Loading

0 comments on commit 74feda2

Please sign in to comment.