Skip to content

Commit 1fe2169

Browse files
committed
Migrate srv files from jsk_pcl_ros to jsk_recognition_msgs
see - jsk-ros-pkg/jsk_recognition#1827 - jsk-ros-pkg/jsk_recognition#1914
1 parent a004d23 commit 1fe2169

File tree

4 files changed

+7
-6
lines changed

4 files changed

+7
-6
lines changed

detect_cans_in_fridge_201202/euslisp/detect_cans.l

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99

1010
(ros::roseus-add-msgs "pcl_msgs")
1111
(ros::roseus-add-srvs "jsk_perception")
12-
(ros::roseus-add-srvs "jsk_pcl_ros")
12+
(ros::roseus-add-srvs "jsk_recognition_msgs")
1313
(ros::roseus-add-msgs "posedetection_msgs")
1414

1515
(defvar *topic-name* "/plane_extraction/output_nonplane_cloud") ;; point cloud from camera
@@ -128,7 +128,7 @@
128128
(defun euclidean-cluster-points (3dp &optional (tolerance 0.01))
129129
(when (or (not 3dp) (= (send 3dp :size) 0))
130130
(return-from euclidean-cluster-points nil))
131-
(let ((req (instance jsk_pcl_ros::EuclideanSegmentRequest :init))
131+
(let ((req (instance jsk_recognition_msgs::EuclideanSegmentRequest :init))
132132
ret)
133133
(send req :input (make-ros-msg-from-eus-pointcloud 3dp :with-color t))
134134
(send req :tolerance tolerance);;

detect_cans_in_fridge_201202/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
<run_depend>roseus</run_depend>
3434
<run_depend>jsk_perception</run_depend>
3535
<run_depend>jsk_pcl_ros</run_depend>
36+
<run_depend>jsk_recognition_msgs</run_depend>
3637
<run_depend>pr2_navigation_self_filter</run_depend>
3738
<run_depend>jsk_pr2_startup</run_depend>
3839
<run_depend>snap_map_icp</run_depend>

jsk_2011_07_pr2_semantic/euslisp/actions.l

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -338,7 +338,7 @@
338338
(dotimes (i 5)
339339
(dotimes (j 5)
340340
(setq 2dpo (v+ 2dpos (float-vector (- (* i 10) 20) (- (* j 10) 20))))
341-
(setq req (instance jsk_pcl_ros::TransformScreenpointRequest :init
341+
(setq req (instance jsk_recognition_msgs::TransformScreenpointRequest :init
342342
:x (elt 2dpo 0) :y (elt 2dpo 1)))
343343
(setq res (ros::service-call ray_srv req))
344344
(setq 3dpos (ros::tf-point->pos (send res :point)))

jsk_2015_06_hrp_drc/drc_task_common/src/drc_task_common/manipulation_data_server.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
#include <pcl/common/transforms.h>
3838
#include <pcl/filters/passthrough.h>
3939
#include <jsk_recognition_msgs/PointsArray.h>
40-
#include <jsk_pcl_ros/ICPAlignWithBox.h>
40+
#include <jsk_recognition_msgs/ICPAlignWithBox.h>
4141
#include <jsk_pcl_ros/pcl_conversion_util.h>
4242
#include <eigen_conversions/eigen_msg.h>
4343
#include <map>
@@ -248,7 +248,7 @@ class ManipulationDataServer
248248
_t_marker_box_pub = _node.advertise<jsk_recognition_msgs::BoundingBox>("/passed_selected_box", 1);
249249
_t_marker_information_pub = _node.advertise<drc_task_common::TMarkerInfo>("/t_marker_information", 1);
250250
subscribe_cloud_and_box();
251-
_icp_client = _node.serviceClient<jsk_pcl_ros::ICPAlignWithBox>("/icp_registration/icp_service");
251+
_icp_client = _node.serviceClient<jsk_recognition_msgs::ICPAlignWithBox>("/icp_registration/icp_service");
252252
_get_type_client = _node.serviceClient<jsk_interactive_marker::GetType>("/transformable_interactive_server/get_type");
253253
_get_pose_client = _node.serviceClient<jsk_interactive_marker::GetTransformableMarkerPose>("/transformable_interactive_server/get_pose");
254254
_get_dim_client = _node.serviceClient<jsk_interactive_marker::GetMarkerDimensions>("/transformable_interactive_server/get_dimensions");
@@ -1234,7 +1234,7 @@ class ManipulationDataServer
12341234
return true;
12351235
}
12361236
jsk_recognition_msgs::ICPResult request_icp(sensor_msgs::PointCloud2 *cloud_msg_ptr, jsk_recognition_msgs::BoundingBox *box_msg_ptr){
1237-
jsk_pcl_ros::ICPAlignWithBox srv;
1237+
jsk_recognition_msgs::ICPAlignWithBox srv;
12381238
srv.request.target_cloud = *cloud_msg_ptr;
12391239
srv.request.target_box = *box_msg_ptr;
12401240
if (_icp_client.call(srv)){

0 commit comments

Comments
 (0)