From 1fe2169293e1b900c4b9c92149723fedfd0fd7ca Mon Sep 17 00:00:00 2001 From: Kentaro Wada Date: Sat, 22 Oct 2016 21:18:34 +0900 Subject: [PATCH] Migrate srv files from jsk_pcl_ros to jsk_recognition_msgs see - https://github.com/jsk-ros-pkg/jsk_recognition/pull/1827 - https://github.com/jsk-ros-pkg/jsk_recognition/pull/1914 --- detect_cans_in_fridge_201202/euslisp/detect_cans.l | 4 ++-- detect_cans_in_fridge_201202/package.xml | 1 + jsk_2011_07_pr2_semantic/euslisp/actions.l | 2 +- .../src/drc_task_common/manipulation_data_server.cpp | 6 +++--- 4 files changed, 7 insertions(+), 6 deletions(-) diff --git a/detect_cans_in_fridge_201202/euslisp/detect_cans.l b/detect_cans_in_fridge_201202/euslisp/detect_cans.l index 7c5ceabb4d..18508e0e8e 100644 --- a/detect_cans_in_fridge_201202/euslisp/detect_cans.l +++ b/detect_cans_in_fridge_201202/euslisp/detect_cans.l @@ -9,7 +9,7 @@ (ros::roseus-add-msgs "pcl_msgs") (ros::roseus-add-srvs "jsk_perception") -(ros::roseus-add-srvs "jsk_pcl_ros") +(ros::roseus-add-srvs "jsk_recognition_msgs") (ros::roseus-add-msgs "posedetection_msgs") (defvar *topic-name* "/plane_extraction/output_nonplane_cloud") ;; point cloud from camera @@ -128,7 +128,7 @@ (defun euclidean-cluster-points (3dp &optional (tolerance 0.01)) (when (or (not 3dp) (= (send 3dp :size) 0)) (return-from euclidean-cluster-points nil)) - (let ((req (instance jsk_pcl_ros::EuclideanSegmentRequest :init)) + (let ((req (instance jsk_recognition_msgs::EuclideanSegmentRequest :init)) ret) (send req :input (make-ros-msg-from-eus-pointcloud 3dp :with-color t)) (send req :tolerance tolerance);; diff --git a/detect_cans_in_fridge_201202/package.xml b/detect_cans_in_fridge_201202/package.xml index 65c8c2da2b..036784ab1b 100644 --- a/detect_cans_in_fridge_201202/package.xml +++ b/detect_cans_in_fridge_201202/package.xml @@ -33,6 +33,7 @@ roseus jsk_perception jsk_pcl_ros + jsk_recognition_msgs pr2_navigation_self_filter jsk_pr2_startup snap_map_icp diff --git a/jsk_2011_07_pr2_semantic/euslisp/actions.l b/jsk_2011_07_pr2_semantic/euslisp/actions.l index 13bba5f2d0..2c98c5e956 100644 --- a/jsk_2011_07_pr2_semantic/euslisp/actions.l +++ b/jsk_2011_07_pr2_semantic/euslisp/actions.l @@ -338,7 +338,7 @@ (dotimes (i 5) (dotimes (j 5) (setq 2dpo (v+ 2dpos (float-vector (- (* i 10) 20) (- (* j 10) 20)))) - (setq req (instance jsk_pcl_ros::TransformScreenpointRequest :init + (setq req (instance jsk_recognition_msgs::TransformScreenpointRequest :init :x (elt 2dpo 0) :y (elt 2dpo 1))) (setq res (ros::service-call ray_srv req)) (setq 3dpos (ros::tf-point->pos (send res :point))) diff --git a/jsk_2015_06_hrp_drc/drc_task_common/src/drc_task_common/manipulation_data_server.cpp b/jsk_2015_06_hrp_drc/drc_task_common/src/drc_task_common/manipulation_data_server.cpp index 3c983855e5..5eb0d81c29 100644 --- a/jsk_2015_06_hrp_drc/drc_task_common/src/drc_task_common/manipulation_data_server.cpp +++ b/jsk_2015_06_hrp_drc/drc_task_common/src/drc_task_common/manipulation_data_server.cpp @@ -37,7 +37,7 @@ #include #include #include -#include +#include #include #include #include @@ -248,7 +248,7 @@ class ManipulationDataServer _t_marker_box_pub = _node.advertise("/passed_selected_box", 1); _t_marker_information_pub = _node.advertise("/t_marker_information", 1); subscribe_cloud_and_box(); - _icp_client = _node.serviceClient("/icp_registration/icp_service"); + _icp_client = _node.serviceClient("/icp_registration/icp_service"); _get_type_client = _node.serviceClient("/transformable_interactive_server/get_type"); _get_pose_client = _node.serviceClient("/transformable_interactive_server/get_pose"); _get_dim_client = _node.serviceClient("/transformable_interactive_server/get_dimensions"); @@ -1234,7 +1234,7 @@ class ManipulationDataServer return true; } jsk_recognition_msgs::ICPResult request_icp(sensor_msgs::PointCloud2 *cloud_msg_ptr, jsk_recognition_msgs::BoundingBox *box_msg_ptr){ - jsk_pcl_ros::ICPAlignWithBox srv; + jsk_recognition_msgs::ICPAlignWithBox srv; srv.request.target_cloud = *cloud_msg_ptr; srv.request.target_box = *box_msg_ptr; if (_icp_client.call(srv)){