From ad690cac915a1002b7870044e82ab04bb6f038c7 Mon Sep 17 00:00:00 2001 From: Kentaro Wada Date: Sat, 22 Oct 2016 21:18:44 +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 --- .../euslisp/collision-detector-client.l | 2 +- jsk_pcl_ros/euslisp/pointcloud_screenpoint.l | 2 +- .../include/jsk_pcl_ros/collision_detector.h | 6 +++--- .../include/jsk_pcl_ros/depth_calibration.h | 2 +- .../jsk_pcl_ros/environment_plane_modeling.h | 4 ++-- .../euclidean_cluster_extraction_nodelet.h | 6 +++--- .../include/jsk_pcl_ros/icp_registration.h | 12 +++++------ .../jsk_pcl_ros/pointcloud_localization.h | 6 +++--- .../jsk_pcl_ros/pointcloud_screenpoint.h | 6 +++--- jsk_pcl_ros/include/jsk_pcl_ros/snapit.h | 8 ++++---- .../scripts/tower_detect_viewer_server.py | 20 +++++++++---------- .../src/collision_detector_nodelet.cpp | 4 ++-- .../euclidean_cluster_extraction_nodelet.cpp | 4 ++-- jsk_pcl_ros/src/icp_registration_nodelet.cpp | 8 ++++---- ...incremental_model_registration_nodelet.cpp | 4 ++-- .../src/pointcloud_localization_nodelet.cpp | 10 +++++----- .../src/pointcloud_screenpoint_nodelet.cpp | 4 ++-- jsk_pcl_ros/src/snapit_nodelet.cpp | 4 ++-- 18 files changed, 56 insertions(+), 56 deletions(-) diff --git a/jsk_pcl_ros/euslisp/collision-detector-client.l b/jsk_pcl_ros/euslisp/collision-detector-client.l index 51091873a4..a5fa187425 100644 --- a/jsk_pcl_ros/euslisp/collision-detector-client.l +++ b/jsk_pcl_ros/euslisp/collision-detector-client.l @@ -46,7 +46,7 @@ () (send *robot* :update-descendants) (let* ((tm (ros::time-now)) - (req (instance jsk_pcl_ros::CheckCollisionRequest :init)) + (req (instance jsk_recognition_msgs::CheckCollisionRequest :init)) res) (send req :joint (instance sensor_msgs::JointState :init diff --git a/jsk_pcl_ros/euslisp/pointcloud_screenpoint.l b/jsk_pcl_ros/euslisp/pointcloud_screenpoint.l index 8504710994..f30e21377b 100755 --- a/jsk_pcl_ros/euslisp/pointcloud_screenpoint.l +++ b/jsk_pcl_ros/euslisp/pointcloud_screenpoint.l @@ -72,7 +72,7 @@ @param msg subscribed msg" (let* ((x (send msg :point :x)) (y (send msg :point :y)) - (req (instance jsk_pcl_ros::TransformScreenpointRequest :init + (req (instance jsk_recognition_msgs::TransformScreenpointRequest :init :x x :y y)) res) ;; call PointcloudScreenPointNodelet::screen_to_point diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/collision_detector.h b/jsk_pcl_ros/include/jsk_pcl_ros/collision_detector.h index 664201b888..27abcabbb2 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/collision_detector.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/collision_detector.h @@ -39,7 +39,7 @@ #include #include -#include +#include #include #include @@ -66,8 +66,8 @@ namespace jsk_pcl_ros virtual bool checkCollision(const sensor_msgs::JointState& joint, const geometry_msgs::PoseStamped& pose); virtual void pointcloudCallback(const sensor_msgs::PointCloud2::ConstPtr& msg); - virtual bool serviceCallback(jsk_pcl_ros::CheckCollision::Request &req, - jsk_pcl_ros::CheckCollision::Response &res); + virtual bool serviceCallback(jsk_recognition_msgs::CheckCollision::Request &req, + jsk_recognition_msgs::CheckCollision::Response &res); boost::mutex mutex_; ros::Subscriber sub_; ros::ServiceServer service_; diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/depth_calibration.h b/jsk_pcl_ros/include/jsk_pcl_ros/depth_calibration.h index 319fd25807..cb3beb60ff 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/depth_calibration.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/depth_calibration.h @@ -38,7 +38,7 @@ #include "pcl_ros/pcl_nodelet.h" #include "jsk_topic_tools/diagnostic_nodelet.h" -#include "jsk_pcl_ros/SetDepthCalibrationParameter.h" +#include "jsk_recognition_msgs/SetDepthCalibrationParameter.h" #include #include #include diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/environment_plane_modeling.h b/jsk_pcl_ros/include/jsk_pcl_ros/environment_plane_modeling.h index e55e588b7c..27c6d4ae70 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/environment_plane_modeling.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/environment_plane_modeling.h @@ -48,8 +48,8 @@ #include #include #include -#include -#include +#include +#include #include #include diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/euclidean_cluster_extraction_nodelet.h b/jsk_pcl_ros/include/jsk_pcl_ros/euclidean_cluster_extraction_nodelet.h index 34413e3a29..cfe059d8fd 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/euclidean_cluster_extraction_nodelet.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/euclidean_cluster_extraction_nodelet.h @@ -54,7 +54,7 @@ #include #include "jsk_recognition_msgs/ClusterPointIndices.h" -#include "jsk_pcl_ros/EuclideanSegment.h" +#include "jsk_recognition_msgs/EuclideanSegment.h" #include "jsk_recognition_msgs/Int32Stamped.h" #include "jsk_pcl_ros/EuclideanClusteringConfig.h" @@ -105,8 +105,8 @@ namespace jsk_pcl_ros virtual void onInit(); virtual void extract(const sensor_msgs::PointCloud2ConstPtr &input); - bool serviceCallback(jsk_pcl_ros::EuclideanSegment::Request &req, - jsk_pcl_ros::EuclideanSegment::Response &res); + bool serviceCallback(jsk_recognition_msgs::EuclideanSegment::Request &req, + jsk_recognition_msgs::EuclideanSegment::Response &res); void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat); virtual std::vector pivotClusterIndices( std::vector& pivot_table, diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/icp_registration.h b/jsk_pcl_ros/include/jsk_pcl_ros/icp_registration.h index 3f78a541e9..ae10adcbfd 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/icp_registration.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/icp_registration.h @@ -41,8 +41,8 @@ #include #include #include -#include -#include +#include +#include #include #include #include @@ -87,11 +87,11 @@ namespace jsk_pcl_ros const sensor_msgs::PointCloud2::ConstPtr& msg, const geometry_msgs::PoseStamped::ConstPtr& pose_msg); virtual bool alignWithBoxService( - jsk_pcl_ros::ICPAlignWithBox::Request& req, - jsk_pcl_ros::ICPAlignWithBox::Response& res); + jsk_recognition_msgs::ICPAlignWithBox::Request& req, + jsk_recognition_msgs::ICPAlignWithBox::Response& res); virtual bool alignService( - jsk_pcl_ros::ICPAlign::Request& req, - jsk_pcl_ros::ICPAlign::Response& res); + jsk_recognition_msgs::ICPAlign::Request& req, + jsk_recognition_msgs::ICPAlign::Response& res); virtual void referenceCallback( const sensor_msgs::PointCloud2::ConstPtr& msg); virtual void referenceArrayCallback( diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/pointcloud_localization.h b/jsk_pcl_ros/include/jsk_pcl_ros/pointcloud_localization.h index bbb0a003f0..f6bd09116e 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/pointcloud_localization.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/pointcloud_localization.h @@ -45,7 +45,7 @@ #include #include #include -#include +#include namespace jsk_pcl_ros { @@ -100,8 +100,8 @@ namespace jsk_pcl_ros * callback function for ~update_offset service */ virtual bool updateOffsetCallback( - jsk_pcl_ros::UpdateOffset::Request& req, - jsk_pcl_ros::UpdateOffset::Response& res); + jsk_recognition_msgs::UpdateOffset::Request& req, + jsk_recognition_msgs::UpdateOffset::Response& res); virtual void applyDownsampling( pcl::PointCloud::Ptr in_cloud, diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/pointcloud_screenpoint.h b/jsk_pcl_ros/include/jsk_pcl_ros/pointcloud_screenpoint.h index 44aff17ab4..1c94f4d6df 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/pointcloud_screenpoint.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/pointcloud_screenpoint.h @@ -50,7 +50,7 @@ #include #include -#include "jsk_pcl_ros/TransformScreenpoint.h" +#include "jsk_recognition_msgs/TransformScreenpoint.h" #include @@ -101,8 +101,8 @@ namespace jsk_pcl_ros #endif void onInit(); - bool screenpoint_cb(jsk_pcl_ros::TransformScreenpoint::Request &req, - jsk_pcl_ros::TransformScreenpoint::Response &res); + bool screenpoint_cb(jsk_recognition_msgs::TransformScreenpoint::Request &req, + jsk_recognition_msgs::TransformScreenpoint::Response &res); void points_cb(const sensor_msgs::PointCloud2ConstPtr &msg); bool checkpoint (pcl::PointCloud< pcl::PointXYZ > &in_pts, int x, int y, diff --git a/jsk_pcl_ros/include/jsk_pcl_ros/snapit.h b/jsk_pcl_ros/include/jsk_pcl_ros/snapit.h index 18280b6200..922f4acb8f 100644 --- a/jsk_pcl_ros/include/jsk_pcl_ros/snapit.h +++ b/jsk_pcl_ros/include/jsk_pcl_ros/snapit.h @@ -44,14 +44,14 @@ #include #include #include -#include "jsk_pcl_ros/CallSnapIt.h" +#include "jsk_recognition_msgs/CallSnapIt.h" #include #include #include "jsk_recognition_utils/geo_util.h" #include #include #include -#include +#include #include "jsk_pcl_ros/tf_listener_singleton.h" namespace jsk_pcl_ros { @@ -88,8 +88,8 @@ namespace jsk_pcl_ros virtual geometry_msgs::PoseStamped alignPose( Eigen::Affine3f& pose, jsk_recognition_utils::ConvexPolygon::Ptr convex); virtual bool footstepAlignServiceCallback( - jsk_pcl_ros::SnapFootstep::Request& req, - jsk_pcl_ros::SnapFootstep::Response& res); + jsk_recognition_msgs::SnapFootstep::Request& req, + jsk_recognition_msgs::SnapFootstep::Response& res); //////////////////////////////////////////////////////// // ROS variables //////////////////////////////////////////////////////// diff --git a/jsk_pcl_ros/scripts/tower_detect_viewer_server.py b/jsk_pcl_ros/scripts/tower_detect_viewer_server.py index cf96b0918d..dd9c07663b 100755 --- a/jsk_pcl_ros/scripts/tower_detect_viewer_server.py +++ b/jsk_pcl_ros/scripts/tower_detect_viewer_server.py @@ -24,8 +24,8 @@ from std_msgs.msg import String from std_msgs.msg import Header from jsk_pcl_ros.msg import Int32Stamped -from jsk_pcl_ros.srv import * -import jsk_pcl_ros.srv +from jsk_recognition_msgs.srv import * +import jsk_recognition_msgs.srv import tf from draw_3d_circle import Drawer3DCircle @@ -58,12 +58,12 @@ def updateState(self, next_state): class TowerDetectViewerServer: # name of tower - TOWER_LOWEST = jsk_pcl_ros.srv.TowerRobotMoveCommandRequest.TOWER_LOWEST - TOWER_MIDDLE = jsk_pcl_ros.srv.TowerRobotMoveCommandRequest.TOWER_MIDDLE - TOWER_HIGHEST = jsk_pcl_ros.srv.TowerRobotMoveCommandRequest.TOWER_HIGHEST - PLATE_SMALL = jsk_pcl_ros.srv.TowerRobotMoveCommandRequest.PLATE_SMALL - PLATE_MIDDLE = jsk_pcl_ros.srv.TowerRobotMoveCommandRequest.PLATE_MIDDLE - PLATE_LARGE = jsk_pcl_ros.srv.TowerRobotMoveCommandRequest.PLATE_LARGE + TOWER_LOWEST = jsk_recognition_msgs.srv.TowerRobotMoveCommandRequest.TOWER_LOWEST + TOWER_MIDDLE = jsk_recognition_msgs.srv.TowerRobotMoveCommandRequest.TOWER_MIDDLE + TOWER_HIGHEST = jsk_recognition_msgs.srv.TowerRobotMoveCommandRequest.TOWER_HIGHEST + PLATE_SMALL = jsk_recognition_msgs.srv.TowerRobotMoveCommandRequest.PLATE_SMALL + PLATE_MIDDLE = jsk_recognition_msgs.srv.TowerRobotMoveCommandRequest.PLATE_MIDDLE + PLATE_LARGE = jsk_recognition_msgs.srv.TowerRobotMoveCommandRequest.PLATE_LARGE PLATE_HEIGHT_LOWEST = 0 PLATE_HEIGHT_MIDDLE = 1 PLATE_HEIGHT_HIGHEST = 2 @@ -195,10 +195,10 @@ def moveRobot(self, plate, from_tower, to_tower, from_height, to_height): self.resolveTowerName(to_tower), self.resolvePlateHeight(to_height))) from_target_position = self.tower_position[from_tower] to_target_position = self.tower_position[to_tower] - self.robot_command(jsk_pcl_ros.srv.TowerRobotMoveCommandRequest.ROBOT1, + self.robot_command(jsk_recognition_msgs.srv.TowerRobotMoveCommandRequest.ROBOT1, plate, from_tower, to_tower, - jsk_pcl_ros.srv.TowerRobotMoveCommandRequest.OPTION_NONE) + jsk_recognition_msgs.srv.TowerRobotMoveCommandRequest.OPTION_NONE) # self.robot_server1(Header(), from_target_position, 0) # self.robot_server1(Header(), to_target_position, 1) def runMain(self): diff --git a/jsk_pcl_ros/src/collision_detector_nodelet.cpp b/jsk_pcl_ros/src/collision_detector_nodelet.cpp index d8c26b8b45..7edd71af70 100644 --- a/jsk_pcl_ros/src/collision_detector_nodelet.cpp +++ b/jsk_pcl_ros/src/collision_detector_nodelet.cpp @@ -131,8 +131,8 @@ namespace jsk_pcl_ros cloud_stamp_ = msg->header.stamp; } - bool CollisionDetector::serviceCallback(jsk_pcl_ros::CheckCollision::Request &req, - jsk_pcl_ros::CheckCollision::Response &res) + bool CollisionDetector::serviceCallback(jsk_recognition_msgs::CheckCollision::Request &req, + jsk_recognition_msgs::CheckCollision::Response &res) { sensor_msgs::JointState joint = req.joint; geometry_msgs::PoseStamped pose = req.pose; diff --git a/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp b/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp index edeedcf1c3..d76b1709f6 100644 --- a/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp +++ b/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp @@ -147,8 +147,8 @@ namespace jsk_pcl_ros bool EuclideanClustering::serviceCallback( - jsk_pcl_ros::EuclideanSegment::Request &req, - jsk_pcl_ros::EuclideanSegment::Response &res) + jsk_recognition_msgs::EuclideanSegment::Request &req, + jsk_recognition_msgs::EuclideanSegment::Response &res) { pcl::PointCloud::Ptr cloud (new pcl::PointCloud); pcl::fromROSMsg(req.input, *cloud); diff --git a/jsk_pcl_ros/src/icp_registration_nodelet.cpp b/jsk_pcl_ros/src/icp_registration_nodelet.cpp index 22d62edc6d..dadecd33a3 100644 --- a/jsk_pcl_ros/src/icp_registration_nodelet.cpp +++ b/jsk_pcl_ros/src/icp_registration_nodelet.cpp @@ -196,8 +196,8 @@ namespace jsk_pcl_ros } bool ICPRegistration::alignWithBoxService( - jsk_pcl_ros::ICPAlignWithBox::Request& req, - jsk_pcl_ros::ICPAlignWithBox::Response& res) + jsk_recognition_msgs::ICPAlignWithBox::Request& req, + jsk_recognition_msgs::ICPAlignWithBox::Response& res) { boost::mutex::scoped_lock lock(mutex_); if (reference_cloud_list_.size() == 0) { @@ -229,8 +229,8 @@ namespace jsk_pcl_ros } bool ICPRegistration::alignService( - jsk_pcl_ros::ICPAlign::Request& req, - jsk_pcl_ros::ICPAlign::Response& res) + jsk_recognition_msgs::ICPAlign::Request& req, + jsk_recognition_msgs::ICPAlign::Response& res) { boost::mutex::scoped_lock lock(mutex_); std::vector::Ptr> tmp_reference_cloud_list diff --git a/jsk_pcl_ros/src/incremental_model_registration_nodelet.cpp b/jsk_pcl_ros/src/incremental_model_registration_nodelet.cpp index 8d97721be1..13a0c9fec7 100644 --- a/jsk_pcl_ros/src/incremental_model_registration_nodelet.cpp +++ b/jsk_pcl_ros/src/incremental_model_registration_nodelet.cpp @@ -39,7 +39,7 @@ #include "jsk_recognition_utils/pcl_conversion_util.h" #include #include -#include +#include namespace jsk_pcl_ros { @@ -177,7 +177,7 @@ namespace jsk_pcl_ros Eigen::Affine3f& output_transform) { ros::ServiceClient icp - = pnh_->serviceClient("icp_service"); + = pnh_->serviceClient("icp_service"); sensor_msgs::PointCloud2 reference_ros, target_ros; pcl::toROSMsg(*reference, reference_ros); pcl::toROSMsg(*target, target_ros); diff --git a/jsk_pcl_ros/src/pointcloud_localization_nodelet.cpp b/jsk_pcl_ros/src/pointcloud_localization_nodelet.cpp index f6fda10df6..94d505777e 100644 --- a/jsk_pcl_ros/src/pointcloud_localization_nodelet.cpp +++ b/jsk_pcl_ros/src/pointcloud_localization_nodelet.cpp @@ -35,7 +35,7 @@ #define BOOST_PARAMETER_MAX_ARITY 7 #include "jsk_pcl_ros/pointcloud_localization.h" -#include +#include #include "jsk_recognition_utils/pcl_conversion_util.h" #include #include @@ -189,8 +189,8 @@ namespace jsk_pcl_ros else { // run ICP ros::ServiceClient client - = pnh_->serviceClient("icp_align"); - jsk_pcl_ros::ICPAlign icp_srv; + = pnh_->serviceClient("icp_align"); + jsk_recognition_msgs::ICPAlign icp_srv; if (clip_unseen_pointcloud_) { // Before running ICP, remove pointcloud where we cannot see @@ -316,8 +316,8 @@ namespace jsk_pcl_ros } bool PointCloudLocalization::updateOffsetCallback( - jsk_pcl_ros::UpdateOffset::Request& req, - jsk_pcl_ros::UpdateOffset::Response& res) + jsk_recognition_msgs::UpdateOffset::Request& req, + jsk_recognition_msgs::UpdateOffset::Response& res) { boost::mutex::scoped_lock lock(mutex_); geometry_msgs::TransformStamped next_pose = req.transformation; diff --git a/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp b/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp index 7576ce0042..e06f21413b 100644 --- a/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp +++ b/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp @@ -186,8 +186,8 @@ bool jsk_pcl_ros::PointcloudScreenpoint::extract_point (pcl::PointCloud< pcl::Po return false; } -bool jsk_pcl_ros::PointcloudScreenpoint::screenpoint_cb (jsk_pcl_ros::TransformScreenpoint::Request &req, - jsk_pcl_ros::TransformScreenpoint::Response &res) +bool jsk_pcl_ros::PointcloudScreenpoint::screenpoint_cb (jsk_recognition_msgs::TransformScreenpoint::Request &req, + jsk_recognition_msgs::TransformScreenpoint::Response &res) { JSK_ROS_DEBUG("PointcloudScreenpoint::screenpoint_cb"); boost::mutex::scoped_lock lock(this->mutex_callback_); diff --git a/jsk_pcl_ros/src/snapit_nodelet.cpp b/jsk_pcl_ros/src/snapit_nodelet.cpp index a5fb7c8ba2..51703d7247 100644 --- a/jsk_pcl_ros/src/snapit_nodelet.cpp +++ b/jsk_pcl_ros/src/snapit_nodelet.cpp @@ -153,8 +153,8 @@ namespace jsk_pcl_ros } bool SnapIt::footstepAlignServiceCallback( - jsk_pcl_ros::SnapFootstep::Request& req, - jsk_pcl_ros::SnapFootstep::Response& res) + jsk_recognition_msgs::SnapFootstep::Request& req, + jsk_recognition_msgs::SnapFootstep::Response& res) { boost::mutex::scoped_lock lock(mutex_); jsk_footstep_msgs::FootstepArray input_footsteps = req.input;