Skip to content

Commit

Permalink
Removed refereces to manipulation
Browse files Browse the repository at this point in the history
  • Loading branch information
Stephanie Eng committed Apr 25, 2022
1 parent 3b9ed7f commit fe3593e
Show file tree
Hide file tree
Showing 8 changed files with 1 addition and 27 deletions.
1 change: 0 additions & 1 deletion .dockerignore
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
!moveit_ros/move_group/package.xml
!moveit_ros/robot_interaction/package.xml
!moveit_ros/visualization/package.xml
!moveit_ros/manipulation/package.xml
!moveit_ros/planning/package.xml
!moveit_ros/planning_interface/package.xml
!moveit_ros/benchmarks/package.xml
Expand Down
1 change: 0 additions & 1 deletion .github/CODEOWNERS.disabled
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,6 @@
/moveit_experimental/ @AndyZe

/moveit_ros/perception/ @jliukkonen @RoboticsYY
/moveit_ros/manipulation/ @v4hn @felixvd
/moveit_ros/benchmarks/ @henningkayser @MohmadAyman
/moveit_ros/planning_interface/ @mintar @rhaschke @felixvd
/moveit_ros/robot_interaction/ @mikeferguson @rhaschke
Expand Down
2 changes: 0 additions & 2 deletions moveit_ros/move_group/src/move_group.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,6 @@ static const char* DEFAULT_CAPABILITIES[] = {
"move_group/MoveGroupKinematicsService",
"move_group/MoveGroupExecuteTrajectoryAction",
"move_group/MoveGroupMoveAction",
// TODO (ddengster) : wait for port for moveit_ros_manipulation package
//"move_group/MoveGroupPickPlaceAction",
"move_group/MoveGroupPlanService",
"move_group/MoveGroupQueryPlannersService",
"move_group/MoveGroupStateValidationService",
Expand Down
3 changes: 0 additions & 3 deletions moveit_ros/moveit_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,6 @@
<exec_depend>moveit_ros_robot_interaction</exec_depend>
<exec_depend>moveit_ros_planning_interface</exec_depend>
<exec_depend>moveit_ros_visualization</exec_depend>
<!--
<exec_depend>moveit_ros_manipulation</exec_depend>
-->
<exec_depend>moveit_ros_move_group</exec_depend>

<test_depend>ament_lint_auto</test_depend>
Expand Down
4 changes: 1 addition & 3 deletions moveit_ros/planning_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,7 @@ find_package(ament_cmake REQUIRED)
find_package(moveit_msgs REQUIRED)
find_package(moveit_core REQUIRED)
find_package(moveit_ros_planning REQUIRED)
find_package(moveit_ros_warehouse REQUIRED)
# find_package(moveit_ros_manipulation REQUIRED)
find_package(moveit_ros_warehouse REQUIRED)]
find_package(moveit_ros_move_group REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(tf2 REQUIRED)
Expand Down Expand Up @@ -51,7 +50,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
moveit_core
moveit_ros_planning
moveit_ros_warehouse
# moveit_ros_manipulation
moveit_ros_move_group
tf2
tf2_eigen
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,10 +62,6 @@
#include <moveit_msgs/srv/get_planner_params.hpp>
#include <moveit_msgs/srv/set_planner_params.hpp>
#include <moveit/utils/rclcpp_utils.h>
// TODO(JafarAbdi): Enable once moveit_ros_manipulation is ported
// #include <moveit_msgs/msg/place_location.hpp>
// #include <moveit_msgs/action/pickup.hpp>
// #include <moveit_msgs/action/place.hpp>

#include <std_msgs/msg/string.hpp>
#include <geometry_msgs/msg/transform_stamped.h>
Expand Down Expand Up @@ -163,14 +159,6 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
move_action_client_ = rclcpp_action::create_client<moveit_msgs::action::MoveGroup>(
pnode_, rclcpp::names::append(opt_.move_group_namespace_, move_group::MOVE_ACTION));
move_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
// TODO(JafarAbdi): Enable once moveit_ros_manipulation is ported
// pick_action_client_ = rclcpp_action::create_client<moveit_msgs::action::Pickup>(
// node_, move_group::PICKUP_ACTION);
// pick_action_client_->wait_for_action_server(std::chrono::nanoseconds(timeout_for_servers.nanoseconds()));
//
// place_action_client_ = rclcpp_action::create_client<moveit_msgs::action::Place>(
// node_, move_group::PLACE_ACTION);
// place_action_client_->wait_for_action_server(std::chrono::nanoseconds(timeout_for_servers.nanoseconds()));
execute_action_client_ = rclcpp_action::create_client<moveit_msgs::action::ExecuteTrajectory>(
pnode_, rclcpp::names::append(opt_.move_group_namespace_, move_group::EXECUTE_ACTION_NAME));
execute_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
Expand Down
2 changes: 0 additions & 2 deletions moveit_ros/planning_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,6 @@
<depend>moveit_ros_planning</depend>
<depend>moveit_ros_warehouse</depend>
<depend>moveit_ros_move_group</depend>
<!-- TODO(JafarAbdi): uncomment after porting moveit_ros_manipulation -->
<!--depend>moveit_ros_manipulation</depend-->
<depend>rclcpp</depend>
<depend>rclpy</depend>
<depend>rclcpp_action</depend>
Expand Down
3 changes: 0 additions & 3 deletions moveit_runtime/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,6 @@
<exec_depend>moveit_core</exec_depend>
<exec_depend>moveit_planners</exec_depend>
<exec_depend>moveit_plugins</exec_depend>
<!--
<exec_depend>moveit_ros_manipulation</exec_depend>
-->
<exec_depend>moveit_ros_move_group</exec_depend>
<!--
TODO(henningkayser): enable after #307 is merged
Expand Down

0 comments on commit fe3593e

Please sign in to comment.