Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Major Release] Migrate srv files from jsk_pcl_ros to jsk_recognition_msgs for #1914 #1917

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions jsk_pcl_ros/euslisp/collision-detector-client.l
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

(ros::roseus-add-msgs "sensor_msgs")
(ros::roseus-add-msgs "geometry_msgs")
(ros::roseus-add-srvs "jsk_pcl_ros")
(ros::roseus-add-srvs "jsk_recognition_msgs")
(ros::roseus-add-msgs "jsk_rviz_plugins")

(defun setup-robot
Expand Down Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions jsk_pcl_ros/euslisp/pointcloud_screenpoint.l
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
;; /ray_target
;; tf of 3D touched point, frame_id is copied from image.
;;
(ros::load-ros-manifest "jsk_pcl_ros")
(ros::load-ros-manifest "jsk_recognition_msgs")
(ros::load-ros-manifest "image_view2")

(defun ros::tf-translation->pos (trans)
Expand Down Expand Up @@ -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
Expand Down
6 changes: 3 additions & 3 deletions jsk_pcl_ros/include/jsk_pcl_ros/collision_detector.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

#include <jsk_topic_tools/diagnostic_nodelet.h>
#include <sensor_msgs/PointCloud2.h>
#include <jsk_pcl_ros/CheckCollision.h>
#include <jsk_recognition_msgs/CheckCollision.h>

#include <pcl/point_types.h>
#include <pcl_ros/transforms.h>
Expand All @@ -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_;
Expand Down
6 changes: 3 additions & 3 deletions jsk_pcl_ros/include/jsk_pcl_ros/depth_calibration.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <message_filters/synchronizer.h>
Expand Down Expand Up @@ -94,8 +94,8 @@ namespace jsk_pcl_ros
}

virtual bool setCalibrationParameter(
SetDepthCalibrationParameter::Request& req,
SetDepthCalibrationParameter::Response& res);
jsk_recognition_msgs::SetDepthCalibrationParameter::Request& req,
jsk_recognition_msgs::SetDepthCalibrationParameter::Response& res);
message_filters::Subscriber<sensor_msgs::Image> sub_input_;
message_filters::Subscriber<sensor_msgs::CameraInfo> sub_camera_info_;
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
Expand Down
4 changes: 2 additions & 2 deletions jsk_pcl_ros/include/jsk_pcl_ros/environment_plane_modeling.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@
#include <jsk_recognition_msgs/ModelCoefficientsArray.h>
#include <jsk_recognition_msgs/ClusterPointIndices.h>
#include <sensor_msgs/PointCloud2.h>
#include <jsk_pcl_ros/EnvironmentLock.h>
#include <jsk_pcl_ros/PolygonOnEnvironment.h>
#include <jsk_recognition_msgs/EnvironmentLock.h>
#include <jsk_recognition_msgs/PolygonOnEnvironment.h>

#include <jsk_recognition_utils/pcl_conversion_util.h>
#include <jsk_pcl_ros/EnvironmentPlaneModelingConfig.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@
#include <pcl/common/centroid.h>

#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"
Expand Down Expand Up @@ -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<pcl::PointIndices> pivotClusterIndices(
std::vector<int>& pivot_table,
Expand Down
12 changes: 6 additions & 6 deletions jsk_pcl_ros/include/jsk_pcl_ros/icp_registration.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,8 @@
#include <dynamic_reconfigure/server.h>
#include <jsk_pcl_ros/ICPRegistrationConfig.h>
#include <jsk_recognition_msgs/BoundingBox.h>
#include <jsk_pcl_ros/ICPAlignWithBox.h>
#include <jsk_pcl_ros/ICPAlign.h>
#include <jsk_recognition_msgs/ICPAlignWithBox.h>
#include <jsk_recognition_msgs/ICPAlign.h>
#include <jsk_recognition_msgs/ICPResult.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
Expand Down Expand Up @@ -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(
Expand Down
6 changes: 3 additions & 3 deletions jsk_pcl_ros/include/jsk_pcl_ros/pointcloud_localization.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
#include <geometry_msgs/PoseStamped.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <jsk_pcl_ros/UpdateOffset.h>
#include <jsk_recognition_msgs/UpdateOffset.h>

namespace jsk_pcl_ros
{
Expand Down Expand Up @@ -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<pcl::PointNormal>::Ptr in_cloud,
Expand Down
6 changes: 3 additions & 3 deletions jsk_pcl_ros/include/jsk_pcl_ros/pointcloud_screenpoint.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/PolygonStamped.h>

#include "jsk_pcl_ros/TransformScreenpoint.h"
#include "jsk_recognition_msgs/TransformScreenpoint.h"

#include <boost/thread/mutex.hpp>

Expand Down Expand Up @@ -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,
Expand Down
8 changes: 4 additions & 4 deletions jsk_pcl_ros/include/jsk_pcl_ros/snapit.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,14 +44,14 @@
#include <geometry_msgs/PolygonStamped.h>
#include <geometry_msgs/PoseArray.h>
#include <jsk_recognition_msgs/ModelCoefficientsArray.h>
#include "jsk_pcl_ros/CallSnapIt.h"
#include "jsk_recognition_msgs/CallSnapIt.h"
#include <tf/transform_listener.h>
#include <jsk_topic_tools/diagnostic_nodelet.h>
#include "jsk_recognition_utils/geo_util.h"
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <message_filters/synchronizer.h>
#include <jsk_pcl_ros/SnapFootstep.h>
#include <jsk_recognition_msgs/SnapFootstep.h>
#include "jsk_pcl_ros/tf_listener_singleton.h"
namespace jsk_pcl_ros
{
Expand Down Expand Up @@ -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
////////////////////////////////////////////////////////
Expand Down
20 changes: 10 additions & 10 deletions jsk_pcl_ros/scripts/tower_detect_viewer_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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):
Expand Down
4 changes: 2 additions & 2 deletions jsk_pcl_ros/src/collision_detector_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions jsk_pcl_ros/src/depth_calibration_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,8 +93,8 @@ namespace jsk_pcl_ros
}

bool DepthCalibration::setCalibrationParameter(
SetDepthCalibrationParameter::Request& req,
SetDepthCalibrationParameter::Response& res)
jsk_recognition_msgs::SetDepthCalibrationParameter::Request& req,
jsk_recognition_msgs::SetDepthCalibrationParameter::Response& res)
{
boost::mutex::scoped_lock lock(mutex_);
coefficients2_ = req.parameter.coefficients2;
Expand Down
4 changes: 2 additions & 2 deletions jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg(req.input, *cloud);
Expand Down
8 changes: 4 additions & 4 deletions jsk_pcl_ros/src/icp_registration_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down Expand Up @@ -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<pcl::PointCloud<PointT>::Ptr> tmp_reference_cloud_list
Expand Down
6 changes: 3 additions & 3 deletions jsk_pcl_ros/src/incremental_model_registration_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#include "jsk_recognition_utils/pcl_conversion_util.h"
#include <pcl/common/transforms.h>
#include <pcl/filters/extract_indices.h>
#include <jsk_pcl_ros/ICPAlign.h>
#include <jsk_recognition_msgs/ICPAlign.h>

namespace jsk_pcl_ros
{
Expand Down Expand Up @@ -177,14 +177,14 @@ namespace jsk_pcl_ros
Eigen::Affine3f& output_transform)
{
ros::ServiceClient icp
= pnh_->serviceClient<jsk_pcl_ros::ICPAlign>("icp_service");
= pnh_->serviceClient<jsk_recognition_msgs::ICPAlign>("icp_service");
sensor_msgs::PointCloud2 reference_ros, target_ros;
pcl::toROSMsg(*reference, reference_ros);
pcl::toROSMsg(*target, target_ros);
ros::Time now = ros::Time::now();
reference_ros.header.stamp = target_ros.header.stamp = now;
reference_ros.header.frame_id = target_ros.header.frame_id = "map";
ICPAlign srv;
jsk_recognition_msgs::ICPAlign srv;
srv.request.reference_cloud = reference_ros;
srv.request.target_cloud = target_ros;
icp.call(srv);
Expand Down
10 changes: 5 additions & 5 deletions jsk_pcl_ros/src/pointcloud_localization_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@

#define BOOST_PARAMETER_MAX_ARITY 7
#include "jsk_pcl_ros/pointcloud_localization.h"
#include <jsk_pcl_ros/ICPAlign.h>
#include <jsk_recognition_msgs/ICPAlign.h>
#include "jsk_recognition_utils/pcl_conversion_util.h"
#include <pcl_ros/transforms.h>
#include <pcl/filters/voxel_grid.h>
Expand Down Expand Up @@ -189,8 +189,8 @@ namespace jsk_pcl_ros
else {
// run ICP
ros::ServiceClient client
= pnh_->serviceClient<jsk_pcl_ros::ICPAlign>("icp_align");
jsk_pcl_ros::ICPAlign icp_srv;
= pnh_->serviceClient<jsk_recognition_msgs::ICPAlign>("icp_align");
jsk_recognition_msgs::ICPAlign icp_srv;

if (clip_unseen_pointcloud_) {
// Before running ICP, remove pointcloud where we cannot see
Expand Down Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
ROS_DEBUG("PointcloudScreenpoint::screenpoint_cb");
boost::mutex::scoped_lock lock(this->mutex_callback_);
Expand Down
4 changes: 2 additions & 2 deletions jsk_pcl_ros/src/snapit_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down