Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Express Humble/Rolling differences in #if #1620

Merged
merged 4 commits into from
Oct 19, 2022
Merged
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
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
set(MOVEIT_LIB_NAME moveit_move_group_interface)

# TODO(#1608): Enable deprecated declarations warning as error once humble support is removed from main branch
add_compile_options(-Wno-deprecated-declarations)

add_library(${MOVEIT_LIB_NAME} SHARED src/move_group_interface.cpp)
include(GenerateExportHeader)
generate_export_header(${MOVEIT_LIB_NAME})
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,8 @@
#include <tf2/utils.h>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_ros/transform_listener.h>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/version.h>

namespace moveit
{
Expand All @@ -84,7 +86,23 @@ enum ActiveTargetType
POSITION,
ORIENTATION
};

// Function to support both Rolling and Humble on the main branch
// Rolling has deprecated the version of the create_client method that takes
// rmw_qos_profile_services_default for the QoS argument
#if RCLCPP_VERSION_GTE(17, 0, 0) // Rolling
auto qos_default()
{
return rclcpp::SystemDefaultsQoS();
}
#else // Humble
auto qos_default()
{
return rmw_qos_profile_services_default;
}
#endif

} // namespace

class MoveGroupInterface::MoveGroupInterfaceImpl
{
Expand Down Expand Up @@ -162,20 +180,17 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
execute_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());

query_service_ = node_->create_client<moveit_msgs::srv::QueryPlannerInterfaces>(
rclcpp::names::append(opt_.move_group_namespace_, move_group::QUERY_PLANNERS_SERVICE_NAME),
rmw_qos_profile_services_default, callback_group_);
rclcpp::names::append(opt_.move_group_namespace_, move_group::QUERY_PLANNERS_SERVICE_NAME), qos_default(),
callback_group_);
get_params_service_ = node_->create_client<moveit_msgs::srv::GetPlannerParams>(
rclcpp::names::append(opt_.move_group_namespace_, move_group::GET_PLANNER_PARAMS_SERVICE_NAME),
rmw_qos_profile_services_default, callback_group_);
rclcpp::names::append(opt_.move_group_namespace_, move_group::GET_PLANNER_PARAMS_SERVICE_NAME), qos_default(),
callback_group_);
set_params_service_ = node_->create_client<moveit_msgs::srv::SetPlannerParams>(
rclcpp::names::append(opt_.move_group_namespace_, move_group::SET_PLANNER_PARAMS_SERVICE_NAME),
rmw_qos_profile_services_default, callback_group_);

rclcpp::names::append(opt_.move_group_namespace_, move_group::SET_PLANNER_PARAMS_SERVICE_NAME), qos_default(),
callback_group_);
cartesian_path_service_ = node_->create_client<moveit_msgs::srv::GetCartesianPath>(
rclcpp::names::append(opt_.move_group_namespace_, move_group::CARTESIAN_PATH_SERVICE_NAME),
rmw_qos_profile_services_default, callback_group_);

// plan_grasps_service_ = pnode_->create_client<moveit_msgs::srv::GraspPlanning>(GRASP_PLANNING_SERVICE_NAME);
rclcpp::names::append(opt_.move_group_namespace_, move_group::CARTESIAN_PATH_SERVICE_NAME), qos_default(),
callback_group_);

RCLCPP_INFO_STREAM(LOGGER, "Ready to take commands for planning group " << opt.group_name_ << ".");
}
Expand Down