Skip to content

Commit

Permalink
Migrate srv files from jsk_pcl_ros to jsk_recognition_msgs
Browse files Browse the repository at this point in the history
  • Loading branch information
wkentaro committed Oct 22, 2016
1 parent a004d23 commit 0efd379
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 5 deletions.
2 changes: 1 addition & 1 deletion detect_cans_in_fridge_201202/euslisp/detect_cans.l
Original file line number Diff line number Diff line change
Expand Up @@ -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);;
Expand Down
2 changes: 1 addition & 1 deletion jsk_2011_07_pr2_semantic/euslisp/actions.l
Original file line number Diff line number Diff line change
Expand Up @@ -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)))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#include <pcl/common/transforms.h>
#include <pcl/filters/passthrough.h>
#include <jsk_recognition_msgs/PointsArray.h>
#include <jsk_pcl_ros/ICPAlignWithBox.h>
#include <jsk_recognition_msgs/ICPAlignWithBox.h>
#include <jsk_pcl_ros/pcl_conversion_util.h>
#include <eigen_conversions/eigen_msg.h>
#include <map>
Expand Down Expand Up @@ -248,7 +248,7 @@ class ManipulationDataServer
_t_marker_box_pub = _node.advertise<jsk_recognition_msgs::BoundingBox>("/passed_selected_box", 1);
_t_marker_information_pub = _node.advertise<drc_task_common::TMarkerInfo>("/t_marker_information", 1);
subscribe_cloud_and_box();
_icp_client = _node.serviceClient<jsk_pcl_ros::ICPAlignWithBox>("/icp_registration/icp_service");
_icp_client = _node.serviceClient<jsk_recognition_msgs::ICPAlignWithBox>("/icp_registration/icp_service");
_get_type_client = _node.serviceClient<jsk_interactive_marker::GetType>("/transformable_interactive_server/get_type");
_get_pose_client = _node.serviceClient<jsk_interactive_marker::GetTransformableMarkerPose>("/transformable_interactive_server/get_pose");
_get_dim_client = _node.serviceClient<jsk_interactive_marker::GetMarkerDimensions>("/transformable_interactive_server/get_dimensions");
Expand Down Expand Up @@ -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)){
Expand Down

0 comments on commit 0efd379

Please sign in to comment.