diff --git a/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp b/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp index 28ebd0c366..b4a2b2b8b8 100644 --- a/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp +++ b/moveit_kinematics/srv_kinematics_plugin/src/srv_kinematics_plugin.cpp @@ -116,7 +116,7 @@ bool SrvKinematicsPlugin::initialize(const moveit::core::RobotModel& robot_model // Create the ROS service client ros::NodeHandle nonprivate_handle(""); ik_service_client_ = std::make_shared( - nonprivate_handle.serviceClient(ik_service_name)); + nonprivate_handle.serviceClient(ik_service_name)); if (!ik_service_client_->waitForExistence(ros::Duration(0.1))) // wait 0.1 seconds, blocking ROS_WARN_STREAM_NAMED("srv", "Unable to connect to ROS service client with name: " << ik_service_client_->getService()); @@ -271,7 +271,7 @@ bool SrvKinematicsPlugin::searchPositionIK(const std::vectorsolve(planning_scene, req, res); return solve_ok; } bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, - const moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::MotionPlanDetailedResponse& res) const + const moveit_msgs::srv::GetMotionPlan::Request& req, moveit_msgs::MotionPlanDetailedResponse& res) const { - moveit_msgs::GetMotionPlan::Response res2; + moveit_msgs::srv::GetMotionPlan::Response res2; if (sbpl_meta_interface_->solve(planning_scene, req, res2)) { res.trajectory_start = res2.trajectory_start; diff --git a/moveit_planners/sbpl/ros/sbpl_interface_ros/src/sbpl_plugin.cpp b/moveit_planners/sbpl/ros/sbpl_interface_ros/src/sbpl_plugin.cpp index e74d4fcdb4..a996914f6f 100644 --- a/moveit_planners/sbpl/ros/sbpl_interface_ros/src/sbpl_plugin.cpp +++ b/moveit_planners/sbpl/ros/sbpl_interface_ros/src/sbpl_plugin.cpp @@ -54,7 +54,7 @@ class SBPLPlanner : public planning_interface::Planner sbpl_interface_.reset(new sbpl_interface::SBPLInterface(model)); } - bool canServiceRequest(const moveit_msgs::GetMotionPlan::Request& req, + bool canServiceRequest(const moveit_msgs::srv::GetMotionPlan::Request& req, planning_interface::PlannerCapability& capabilities) const { // TODO: this is a dummy implementation @@ -63,7 +63,7 @@ class SBPLPlanner : public planning_interface::Planner } bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, - const moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::GetMotionPlan::Response& res) const + const moveit_msgs::srv::GetMotionPlan::Request& req, moveit_msgs::srv::GetMotionPlan::Response& res) const { sbpl_interface::PlanningParameters params; params.use_bfs_ = false; @@ -72,12 +72,12 @@ class SBPLPlanner : public planning_interface::Planner } bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, - const moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::MotionPlanDetailedResponse& res) const + const moveit_msgs::srv::GetMotionPlan::Request& req, moveit_msgs::MotionPlanDetailedResponse& res) const { sbpl_interface::PlanningParameters params; params.use_bfs_ = false; - moveit_msgs::GetMotionPlan::Response res2; + moveit_msgs::srv::GetMotionPlan::Response res2; if (sbpl_interface_->solve(planning_scene, req, res2, params)) { res.trajectory_start = res2.trajectory_start; diff --git a/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.cpp index 2564ea3de6..fe7c04da93 100644 --- a/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.cpp @@ -47,8 +47,8 @@ void move_group::ApplyPlanningSceneService::initialize() &ApplyPlanningSceneService::applyScene, this); } -bool move_group::ApplyPlanningSceneService::applyScene(moveit_msgs::ApplyPlanningScene::Request& req, - moveit_msgs::ApplyPlanningScene::Response& res) +bool move_group::ApplyPlanningSceneService::applyScene(moveit_msgs::srv::ApplyPlanningScene::Request& req, + moveit_msgs::srv::ApplyPlanningScene::Response& res) { if (!context_->planning_scene_monitor_) { diff --git a/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h b/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h index 3bcd7aeec2..8968eebe89 100644 --- a/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h @@ -54,7 +54,7 @@ class ApplyPlanningSceneService : public MoveGroupCapability void initialize() override; private: - bool applyScene(moveit_msgs::ApplyPlanningScene::Request& req, moveit_msgs::ApplyPlanningScene::Response& res); + bool applyScene(moveit_msgs::srv::ApplyPlanningScene::Request& req, moveit_msgs::srv::ApplyPlanningScene::Response& res); ros::ServiceServer service_; }; diff --git a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp index 9fa9fad9e0..9186a4b2fd 100644 --- a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp @@ -70,8 +70,8 @@ bool isStateValid(const planning_scene::PlanningScene* planning_scene, } } -bool move_group::MoveGroupCartesianPathService::computeService(moveit_msgs::GetCartesianPath::Request& req, - moveit_msgs::GetCartesianPath::Response& res) +bool move_group::MoveGroupCartesianPathService::computeService(moveit_msgs::srv::GetCartesianPath::Request& req, + moveit_msgs::srv::GetCartesianPath::Response& res) { ROS_INFO("Received request to compute Cartesian path"); context_->planning_scene_monitor_->updateFrameTransforms(); diff --git a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h index cf1fbe9a47..93cc084244 100644 --- a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h @@ -50,7 +50,7 @@ class MoveGroupCartesianPathService : public MoveGroupCapability void initialize() override; private: - bool computeService(moveit_msgs::GetCartesianPath::Request& req, moveit_msgs::GetCartesianPath::Response& res); + bool computeService(moveit_msgs::srv::GetCartesianPath::Request& req, moveit_msgs::srv::GetCartesianPath::Response& res); ros::ServiceServer cartesian_path_service_; ros::Publisher display_path_; diff --git a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_service_capability.cpp index 52a9873422..4d3c9ca2b3 100644 --- a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_service_capability.cpp @@ -57,15 +57,15 @@ void move_group::MoveGroupExecuteService::initialize() // execution of the main spinner thread. // Hence, we use our own asynchronous spinner listening to our own callback queue. ros::AdvertiseServiceOptions ops; - ops.template init( + ops.template init( EXECUTE_SERVICE_NAME, boost::bind(&MoveGroupExecuteService::executeTrajectoryService, this, _1, _2)); ops.callback_queue = &callback_queue_; execute_service_ = root_node_handle_.advertiseService(ops); spinner_.start(); } -bool move_group::MoveGroupExecuteService::executeTrajectoryService(moveit_msgs::ExecuteKnownTrajectory::Request& req, - moveit_msgs::ExecuteKnownTrajectory::Response& res) +bool move_group::MoveGroupExecuteService::executeTrajectoryService(moveit_msgs::srv::ExecuteKnownTrajectory::Request& req, + moveit_msgs::srv::ExecuteKnownTrajectory::Response& res) { ROS_INFO("Received new trajectory execution service request..."); if (!context_->trajectory_execution_manager_) diff --git a/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.cpp index 19dd298b8c..6d4cbc2df7 100644 --- a/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.cpp @@ -48,8 +48,8 @@ void move_group::MoveGroupGetPlanningSceneService::initialize() GET_PLANNING_SCENE_SERVICE_NAME, &MoveGroupGetPlanningSceneService::getPlanningSceneService, this); } -bool move_group::MoveGroupGetPlanningSceneService::getPlanningSceneService(moveit_msgs::GetPlanningScene::Request& req, - moveit_msgs::GetPlanningScene::Response& res) +bool move_group::MoveGroupGetPlanningSceneService::getPlanningSceneService(moveit_msgs::srv::GetPlanningScene::Request& req, + moveit_msgs::srv::GetPlanningScene::Response& res) { if (req.components.components & moveit_msgs::PlanningSceneComponents::TRANSFORMS) context_->planning_scene_monitor_->updateFrameTransforms(); diff --git a/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h b/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h index 63fd7c35e7..572d0df35a 100644 --- a/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h @@ -50,8 +50,8 @@ class MoveGroupGetPlanningSceneService : public MoveGroupCapability void initialize() override; private: - bool getPlanningSceneService(moveit_msgs::GetPlanningScene::Request& req, - moveit_msgs::GetPlanningScene::Response& res); + bool getPlanningSceneService(moveit_msgs::srv::GetPlanningScene::Request& req, + moveit_msgs::srv::GetPlanningScene::Response& res); ros::ServiceServer get_scene_service_; }; diff --git a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp index 1d321f1ba7..19742fed55 100644 --- a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp @@ -140,8 +140,8 @@ void move_group::MoveGroupKinematicsService::computeIK( error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME; } -bool move_group::MoveGroupKinematicsService::computeIKService(moveit_msgs::GetPositionIK::Request& req, - moveit_msgs::GetPositionIK::Response& res) +bool move_group::MoveGroupKinematicsService::computeIKService(moveit_msgs::srv::GetPositionIK::Request& req, + moveit_msgs::srv::GetPositionIK::Response& res) { context_->planning_scene_monitor_->updateFrameTransforms(); @@ -169,8 +169,8 @@ bool move_group::MoveGroupKinematicsService::computeIKService(moveit_msgs::GetPo return true; } -bool move_group::MoveGroupKinematicsService::computeFKService(moveit_msgs::GetPositionFK::Request& req, - moveit_msgs::GetPositionFK::Response& res) +bool move_group::MoveGroupKinematicsService::computeFKService(moveit_msgs::srv::GetPositionFK::Request& req, + moveit_msgs::srv::GetPositionFK::Response& res) { if (req.fk_link_names.empty()) { diff --git a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h index d1f10a96a5..99573b16e5 100644 --- a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h @@ -51,8 +51,8 @@ class MoveGroupKinematicsService : public MoveGroupCapability void initialize() override; private: - bool computeIKService(moveit_msgs::GetPositionIK::Request& req, moveit_msgs::GetPositionIK::Response& res); - bool computeFKService(moveit_msgs::GetPositionFK::Request& req, moveit_msgs::GetPositionFK::Response& res); + bool computeIKService(moveit_msgs::srv::GetPositionIK::Request& req, moveit_msgs::srv::GetPositionIK::Response& res); + bool computeFKService(moveit_msgs::srv::GetPositionFK::Request& req, moveit_msgs::srv::GetPositionFK::Response& res); void computeIK( moveit_msgs::PositionIKRequest& req, moveit_msgs::RobotState& solution, moveit_msgs::MoveItErrorCodes& error_code, diff --git a/moveit_ros/move_group/src/default_capabilities/plan_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/plan_service_capability.cpp index 145bbb9792..f36e62a8fe 100644 --- a/moveit_ros/move_group/src/default_capabilities/plan_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/plan_service_capability.cpp @@ -48,8 +48,8 @@ void move_group::MoveGroupPlanService::initialize() root_node_handle_.advertiseService(PLANNER_SERVICE_NAME, &MoveGroupPlanService::computePlanService, this); } -bool move_group::MoveGroupPlanService::computePlanService(moveit_msgs::GetMotionPlan::Request& req, - moveit_msgs::GetMotionPlan::Response& res) +bool move_group::MoveGroupPlanService::computePlanService(moveit_msgs::srv::GetMotionPlan::Request& req, + moveit_msgs::srv::GetMotionPlan::Response& res) { ROS_INFO("Received new planning service request..."); // before we start planning, ensure that we have the latest robot state received... diff --git a/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h b/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h index b3d7a94250..d098cd6508 100644 --- a/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h @@ -50,7 +50,7 @@ class MoveGroupPlanService : public MoveGroupCapability void initialize() override; private: - bool computePlanService(moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::GetMotionPlan::Response& res); + bool computePlanService(moveit_msgs::srv::GetMotionPlan::Request& req, moveit_msgs::srv::GetMotionPlan::Response& res); ros::ServiceServer plan_service_; }; diff --git a/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.cpp index 90df326c31..1e714e2840 100644 --- a/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.cpp @@ -53,8 +53,8 @@ void move_group::MoveGroupQueryPlannersService::initialize() &MoveGroupQueryPlannersService::setParams, this); } -bool move_group::MoveGroupQueryPlannersService::queryInterface(moveit_msgs::QueryPlannerInterfaces::Request& req, - moveit_msgs::QueryPlannerInterfaces::Response& res) +bool move_group::MoveGroupQueryPlannersService::queryInterface(moveit_msgs::srv::QueryPlannerInterfaces::Request& req, + moveit_msgs::srv::QueryPlannerInterfaces::Response& res) { const planning_interface::PlannerManagerPtr& planner_interface = context_->planning_pipeline_->getPlannerManager(); if (planner_interface) @@ -69,8 +69,8 @@ bool move_group::MoveGroupQueryPlannersService::queryInterface(moveit_msgs::Quer return true; } -bool move_group::MoveGroupQueryPlannersService::getParams(moveit_msgs::GetPlannerParams::Request& req, - moveit_msgs::GetPlannerParams::Response& res) +bool move_group::MoveGroupQueryPlannersService::getParams(moveit_msgs::srv::GetPlannerParams::Request& req, + moveit_msgs::srv::GetPlannerParams::Response& res) { const planning_interface::PlannerManagerPtr& planner_interface = context_->planning_pipeline_->getPlannerManager(); if (planner_interface) @@ -100,8 +100,8 @@ bool move_group::MoveGroupQueryPlannersService::getParams(moveit_msgs::GetPlanne return true; } -bool move_group::MoveGroupQueryPlannersService::setParams(moveit_msgs::SetPlannerParams::Request& req, - moveit_msgs::SetPlannerParams::Response& res) +bool move_group::MoveGroupQueryPlannersService::setParams(moveit_msgs::srv::SetPlannerParams::Request& req, + moveit_msgs::srv::SetPlannerParams::Response& res) { const planning_interface::PlannerManagerPtr& planner_interface = context_->planning_pipeline_->getPlannerManager(); if (req.params.keys.size() != req.params.values.size()) diff --git a/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h b/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h index 656c228a08..4e97628840 100644 --- a/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h @@ -52,11 +52,11 @@ class MoveGroupQueryPlannersService : public MoveGroupCapability void initialize() override; private: - bool queryInterface(moveit_msgs::QueryPlannerInterfaces::Request& req, - moveit_msgs::QueryPlannerInterfaces::Response& res); + bool queryInterface(moveit_msgs::srv::QueryPlannerInterfaces::Request& req, + moveit_msgs::srv::QueryPlannerInterfaces::Response& res); - bool getParams(moveit_msgs::GetPlannerParams::Request& req, moveit_msgs::GetPlannerParams::Response& res); - bool setParams(moveit_msgs::SetPlannerParams::Request& req, moveit_msgs::SetPlannerParams::Response& res); + bool getParams(moveit_msgs::srv::GetPlannerParams::Request& req, moveit_msgs::srv::GetPlannerParams::Response& res); + bool setParams(moveit_msgs::srv::SetPlannerParams::Request& req, moveit_msgs::srv::SetPlannerParams::Response& res); ros::ServiceServer query_service_; ros::ServiceServer get_service_; diff --git a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp index 8ceb1f7ff3..a7e4819b97 100644 --- a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp @@ -51,8 +51,8 @@ void move_group::MoveGroupStateValidationService::initialize() &MoveGroupStateValidationService::computeService, this); } -bool move_group::MoveGroupStateValidationService::computeService(moveit_msgs::GetStateValidity::Request& req, - moveit_msgs::GetStateValidity::Response& res) +bool move_group::MoveGroupStateValidationService::computeService(moveit_msgs::srv::GetStateValidity::Request& req, + moveit_msgs::srv::GetStateValidity::Response& res) { planning_scene_monitor::LockedPlanningSceneRO ls(context_->planning_scene_monitor_); robot_state::RobotState rs = ls->getCurrentState(); diff --git a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h index 2806a9586c..a2de92684f 100644 --- a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h @@ -50,7 +50,7 @@ class MoveGroupStateValidationService : public MoveGroupCapability void initialize() override; private: - bool computeService(moveit_msgs::GetStateValidity::Request& req, moveit_msgs::GetStateValidity::Response& res); + bool computeService(moveit_msgs::srv::GetStateValidity::Request& req, moveit_msgs::srv::GetStateValidity::Response& res); ros::ServiceServer validity_service_; }; diff --git a/moveit_ros/perception/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/perception/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index 1558c434ae..aa0877deab 100644 --- a/moveit_ros/perception/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/perception/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -128,10 +128,10 @@ class OccupancyMapMonitor void initialize(); /** @brief Save the current octree to a binary file */ - bool saveMapCallback(moveit_msgs::SaveMap::Request& request, moveit_msgs::SaveMap::Response& response); + bool saveMapCallback(moveit_msgs::srv::SaveMap::Request& request, moveit_msgs::srv::SaveMap::Response& response); /** @brief Load octree from a binary file (gets rid of current octree data) */ - bool loadMapCallback(moveit_msgs::LoadMap::Request& request, moveit_msgs::LoadMap::Response& response); + bool loadMapCallback(moveit_msgs::srv::LoadMap::Request& request, moveit_msgs::srv::LoadMap::Response& response); bool getShapeTransformCache(std::size_t index, const std::string& target_frame, const ros::Time& target_time, ShapeTransformCache& cache) const; diff --git a/moveit_ros/perception/occupancy_map_monitor/src/occupancy_map_monitor.cpp b/moveit_ros/perception/occupancy_map_monitor/src/occupancy_map_monitor.cpp index 1df0ef30cd..10049f627b 100644 --- a/moveit_ros/perception/occupancy_map_monitor/src/occupancy_map_monitor.cpp +++ b/moveit_ros/perception/occupancy_map_monitor/src/occupancy_map_monitor.cpp @@ -295,8 +295,8 @@ bool OccupancyMapMonitor::getShapeTransformCache(std::size_t index, const std::s return false; } -bool OccupancyMapMonitor::saveMapCallback(moveit_msgs::SaveMap::Request& request, - moveit_msgs::SaveMap::Response& response) +bool OccupancyMapMonitor::saveMapCallback(moveit_msgs::srv::SaveMap::Request& request, + moveit_msgs::srv::SaveMap::Response& response) { ROS_INFO("Writing map to %s", request.filename.c_str()); tree_->lockRead(); @@ -312,8 +312,8 @@ bool OccupancyMapMonitor::saveMapCallback(moveit_msgs::SaveMap::Request& request return true; } -bool OccupancyMapMonitor::loadMapCallback(moveit_msgs::LoadMap::Request& request, - moveit_msgs::LoadMap::Response& response) +bool OccupancyMapMonitor::loadMapCallback(moveit_msgs::srv::LoadMap::Request& request, + moveit_msgs::srv::LoadMap::Response& response) { ROS_INFO("Reading map from %s", request.filename.c_str()); diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index 103e5e229b..e1f1bdd530 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -335,7 +335,7 @@ class PlanningSceneMonitor : private boost::noncopyable /** @brief Request planning scene state using a service call * @param service_name The name of the service to use for requesting the * planning scene. This must be a service of type - * moveit_msgs::GetPlanningScene and is usually called + * moveit_msgs::srv::GetPlanningScene and is usually called * "/get_planning_scene". */ bool requestPlanningSceneState(const std::string& service_name = DEFAULT_PLANNING_SCENE_SERVICE); diff --git a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp index 83f8b56610..b10c8a38a4 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp @@ -469,8 +469,8 @@ void PlanningSceneMonitor::triggerSceneUpdateEvent(SceneUpdateType update_type) bool PlanningSceneMonitor::requestPlanningSceneState(const std::string& service_name) { // use global namespace for service - ros::ServiceClient client = ros::NodeHandle().serviceClient(service_name); - moveit_msgs::GetPlanningScene srv; + ros::ServiceClient client = ros::NodeHandle().serviceClient(service_name); + moveit_msgs::srv::GetPlanningScene srv; srv.request.components.components = srv.request.components.SCENE_SETTINGS | srv.request.components.ROBOT_STATE | srv.request.components.ROBOT_STATE_ATTACHED_OBJECTS | srv.request.components.WORLD_OBJECT_NAMES | diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index 1b7f57d960..eb5fc4268b 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -779,12 +779,12 @@ class MoveGroupInterface /** \brief Pick up an object - calls the external moveit_msgs::GraspPlanning service "plan_grasps" to compute possible grasps */ + calls the external moveit_msgs::srv::GraspPlanning service "plan_grasps" to compute possible grasps */ MoveItErrorCode planGraspsAndPick(const std::string& object = "", bool plan_only = false); /** \brief Pick up an object - calls the external moveit_msgs::GraspPlanning service "plan_grasps" to compute possible grasps */ + calls the external moveit_msgs::srv::GraspPlanning service "plan_grasps" to compute possible grasps */ MoveItErrorCode planGraspsAndPick(const moveit_msgs::CollisionObject& object, bool plan_only = false); /** \brief Place an object somewhere safe in the world (a safe location will be detected) */ diff --git a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp index f34aa7d4ae..7484d3fd32 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp @@ -161,16 +161,16 @@ class MoveGroupInterface::MoveGroupInterfaceImpl waitForAction(execute_action_client_, move_group::EXECUTE_ACTION_NAME, timeout_for_servers, allotted_time); query_service_ = - node_handle_.serviceClient(move_group::QUERY_PLANNERS_SERVICE_NAME); + node_handle_.serviceClient(move_group::QUERY_PLANNERS_SERVICE_NAME); get_params_service_ = - node_handle_.serviceClient(move_group::GET_PLANNER_PARAMS_SERVICE_NAME); + node_handle_.serviceClient(move_group::GET_PLANNER_PARAMS_SERVICE_NAME); set_params_service_ = - node_handle_.serviceClient(move_group::SET_PLANNER_PARAMS_SERVICE_NAME); + node_handle_.serviceClient(move_group::SET_PLANNER_PARAMS_SERVICE_NAME); cartesian_path_service_ = - node_handle_.serviceClient(move_group::CARTESIAN_PATH_SERVICE_NAME); + node_handle_.serviceClient(move_group::CARTESIAN_PATH_SERVICE_NAME); - plan_grasps_service_ = node_handle_.serviceClient(GRASP_PLANNING_SERVICE_NAME); + plan_grasps_service_ = node_handle_.serviceClient(GRASP_PLANNING_SERVICE_NAME); ROS_INFO_STREAM_NAMED("move_group_interface", "Ready to take commands for planning group " << opt.group_name_ << "."); @@ -265,8 +265,8 @@ class MoveGroupInterface::MoveGroupInterfaceImpl bool getInterfaceDescription(moveit_msgs::PlannerInterfaceDescription& desc) { - moveit_msgs::QueryPlannerInterfaces::Request req; - moveit_msgs::QueryPlannerInterfaces::Response res; + moveit_msgs::srv::QueryPlannerInterfaces::Request req; + moveit_msgs::srv::QueryPlannerInterfaces::Response res; if (query_service_.call(req, res)) if (!res.planner_interfaces.empty()) { @@ -278,8 +278,8 @@ class MoveGroupInterface::MoveGroupInterfaceImpl std::map getPlannerParams(const std::string& planner_id, const std::string& group = "") { - moveit_msgs::GetPlannerParams::Request req; - moveit_msgs::GetPlannerParams::Response res; + moveit_msgs::srv::GetPlannerParams::Request req; + moveit_msgs::srv::GetPlannerParams::Response res; req.planner_config = planner_id; req.group = group; std::map result; @@ -294,8 +294,8 @@ class MoveGroupInterface::MoveGroupInterfaceImpl void setPlannerParams(const std::string& planner_id, const std::string& group, const std::map& params, bool replace = false) { - moveit_msgs::SetPlannerParams::Request req; - moveit_msgs::SetPlannerParams::Response res; + moveit_msgs::srv::SetPlannerParams::Request req; + moveit_msgs::srv::SetPlannerParams::Response res; req.planner_config = planner_id; req.group = group; req.replace = replace; @@ -714,8 +714,8 @@ class MoveGroupInterface::MoveGroupInterfaceImpl return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::FAILURE); } - moveit_msgs::GraspPlanning::Request request; - moveit_msgs::GraspPlanning::Response response; + moveit_msgs::srv::GraspPlanning::Request request; + moveit_msgs::srv::GraspPlanning::Response response; request.group_name = opt_.group_name_; request.target = object; @@ -851,8 +851,8 @@ class MoveGroupInterface::MoveGroupInterfaceImpl moveit_msgs::RobotTrajectory& msg, const moveit_msgs::Constraints& path_constraints, bool avoid_collisions, moveit_msgs::MoveItErrorCodes& error_code) { - moveit_msgs::GetCartesianPath::Request req; - moveit_msgs::GetCartesianPath::Response res; + moveit_msgs::srv::GetCartesianPath::Request req; + moveit_msgs::srv::GetCartesianPath::Response res; if (considered_start_state_) robot_state::robotStateToRobotStateMsg(*considered_start_state_, req.start_state); diff --git a/moveit_ros/planning_interface/planning_scene_interface/src/planning_scene_interface.cpp b/moveit_ros/planning_interface/planning_scene_interface/src/planning_scene_interface.cpp index 7952a2e08b..ea92b39d64 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/src/planning_scene_interface.cpp +++ b/moveit_ros/planning_interface/planning_scene_interface/src/planning_scene_interface.cpp @@ -52,16 +52,16 @@ class PlanningSceneInterface::PlanningSceneInterfaceImpl { node_handle_ = ros::NodeHandle(ns); planning_scene_service_ = - node_handle_.serviceClient(move_group::GET_PLANNING_SCENE_SERVICE_NAME); + node_handle_.serviceClient(move_group::GET_PLANNING_SCENE_SERVICE_NAME); apply_planning_scene_service_ = - node_handle_.serviceClient(move_group::APPLY_PLANNING_SCENE_SERVICE_NAME); + node_handle_.serviceClient(move_group::APPLY_PLANNING_SCENE_SERVICE_NAME); planning_scene_diff_publisher_ = node_handle_.advertise("planning_scene", 1); } std::vector getKnownObjectNames(bool with_type) { - moveit_msgs::GetPlanningScene::Request request; - moveit_msgs::GetPlanningScene::Response response; + moveit_msgs::srv::GetPlanningScene::Request request; + moveit_msgs::srv::GetPlanningScene::Response response; std::vector result; request.components.components = request.components.WORLD_OBJECT_NAMES; if (!planning_scene_service_.call(request, response)) @@ -83,8 +83,8 @@ class PlanningSceneInterface::PlanningSceneInterfaceImpl std::vector getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz, bool with_type, std::vector& types) { - moveit_msgs::GetPlanningScene::Request request; - moveit_msgs::GetPlanningScene::Response response; + moveit_msgs::srv::GetPlanningScene::Request request; + moveit_msgs::srv::GetPlanningScene::Response response; std::vector result; request.components.components = request.components.WORLD_OBJECT_GEOMETRY; if (!planning_scene_service_.call(request, response)) @@ -135,8 +135,8 @@ class PlanningSceneInterface::PlanningSceneInterfaceImpl std::map getObjectPoses(const std::vector& object_ids) { - moveit_msgs::GetPlanningScene::Request request; - moveit_msgs::GetPlanningScene::Response response; + moveit_msgs::srv::GetPlanningScene::Request request; + moveit_msgs::srv::GetPlanningScene::Response response; std::map result; request.components.components = request.components.WORLD_OBJECT_GEOMETRY; if (!planning_scene_service_.call(request, response)) @@ -166,8 +166,8 @@ class PlanningSceneInterface::PlanningSceneInterfaceImpl std::map getObjects(const std::vector& object_ids) { - moveit_msgs::GetPlanningScene::Request request; - moveit_msgs::GetPlanningScene::Response response; + moveit_msgs::srv::GetPlanningScene::Request request; + moveit_msgs::srv::GetPlanningScene::Response response; std::map result; request.components.components = request.components.WORLD_OBJECT_GEOMETRY; if (!planning_scene_service_.call(request, response)) @@ -191,8 +191,8 @@ class PlanningSceneInterface::PlanningSceneInterfaceImpl std::map getAttachedObjects(const std::vector& object_ids) { - moveit_msgs::GetPlanningScene::Request request; - moveit_msgs::GetPlanningScene::Response response; + moveit_msgs::srv::GetPlanningScene::Request request; + moveit_msgs::srv::GetPlanningScene::Response response; std::map result; request.components.components = request.components.ROBOT_STATE_ATTACHED_OBJECTS; if (!planning_scene_service_.call(request, response)) @@ -217,8 +217,8 @@ class PlanningSceneInterface::PlanningSceneInterfaceImpl bool applyPlanningScene(const moveit_msgs::PlanningScene& planning_scene) { - moveit_msgs::ApplyPlanningScene::Request request; - moveit_msgs::ApplyPlanningScene::Response response; + moveit_msgs::srv::ApplyPlanningScene::Request request; + moveit_msgs::srv::ApplyPlanningScene::Response response; request.scene = planning_scene; if (!apply_planning_scene_service_.call(request, response)) { diff --git a/moveit_ros/warehouse/warehouse/src/warehouse_services.cpp b/moveit_ros/warehouse/warehouse/src/warehouse_services.cpp index 7a18a52aed..03a59ef04e 100644 --- a/moveit_ros/warehouse/warehouse/src/warehouse_services.cpp +++ b/moveit_ros/warehouse/warehouse/src/warehouse_services.cpp @@ -45,8 +45,8 @@ static const std::string ROBOT_DESCRIPTION = "robot_description"; -bool storeState(moveit_msgs::SaveRobotStateToWarehouse::Request& request, - moveit_msgs::SaveRobotStateToWarehouse::Response& response, moveit_warehouse::RobotStateStorage* rs) +bool storeState(moveit_msgs::srv::SaveRobotStateToWarehouse::Request& request, + moveit_msgs::srv::SaveRobotStateToWarehouse::Response& response, moveit_warehouse::RobotStateStorage* rs) { if (request.name.empty()) { @@ -57,8 +57,8 @@ bool storeState(moveit_msgs::SaveRobotStateToWarehouse::Request& request, return (response.success = true); } -bool listStates(moveit_msgs::ListRobotStatesInWarehouse::Request& request, - moveit_msgs::ListRobotStatesInWarehouse::Response& response, moveit_warehouse::RobotStateStorage* rs) +bool listStates(moveit_msgs::srv::ListRobotStatesInWarehouse::Request& request, + moveit_msgs::srv::ListRobotStatesInWarehouse::Response& response, moveit_warehouse::RobotStateStorage* rs) { if (request.regex.empty()) { @@ -71,16 +71,16 @@ bool listStates(moveit_msgs::ListRobotStatesInWarehouse::Request& request, return true; } -bool hasState(moveit_msgs::CheckIfRobotStateExistsInWarehouse::Request& request, - moveit_msgs::CheckIfRobotStateExistsInWarehouse::Response& response, +bool hasState(moveit_msgs::srv::CheckIfRobotStateExistsInWarehouse::Request& request, + moveit_msgs::srv::CheckIfRobotStateExistsInWarehouse::Response& response, moveit_warehouse::RobotStateStorage* rs) { response.exists = rs->hasRobotState(request.name, request.robot); return true; } -bool getState(moveit_msgs::GetRobotStateFromWarehouse::Request& request, - moveit_msgs::GetRobotStateFromWarehouse::Response& response, moveit_warehouse::RobotStateStorage* rs) +bool getState(moveit_msgs::srv::GetRobotStateFromWarehouse::Request& request, + moveit_msgs::srv::GetRobotStateFromWarehouse::Response& response, moveit_warehouse::RobotStateStorage* rs) { if (!rs->hasRobotState(request.name, request.robot)) { @@ -95,8 +95,8 @@ bool getState(moveit_msgs::GetRobotStateFromWarehouse::Request& request, return true; } -bool renameState(moveit_msgs::RenameRobotStateInWarehouse::Request& request, - moveit_msgs::RenameRobotStateInWarehouse::Response& response, moveit_warehouse::RobotStateStorage* rs) +bool renameState(moveit_msgs::srv::RenameRobotStateInWarehouse::Request& request, + moveit_msgs::srv::RenameRobotStateInWarehouse::Response& response, moveit_warehouse::RobotStateStorage* rs) { if (!rs->hasRobotState(request.old_name, request.robot)) { @@ -107,8 +107,8 @@ bool renameState(moveit_msgs::RenameRobotStateInWarehouse::Request& request, return true; } -bool deleteState(moveit_msgs::DeleteRobotStateFromWarehouse::Request& request, - moveit_msgs::DeleteRobotStateFromWarehouse::Response& response, +bool deleteState(moveit_msgs::srv::DeleteRobotStateFromWarehouse::Request& request, + moveit_msgs::srv::DeleteRobotStateFromWarehouse::Response& response, moveit_warehouse::RobotStateStorage* rs) { if (!rs->hasRobotState(request.name, request.robot)) @@ -178,28 +178,28 @@ int main(int argc, char** argv) ROS_INFO(" * %s", names[i].c_str()); } - boost::function + boost::function save_cb = boost::bind(&storeState, _1, _2, &rs); - boost::function + boost::function list_cb = boost::bind(&listStates, _1, _2, &rs); - boost::function + boost::function get_cb = boost::bind(&getState, _1, _2, &rs); - boost::function + boost::function has_cb = boost::bind(&hasState, _1, _2, &rs); - boost::function + boost::function rename_cb = boost::bind(&renameState, _1, _2, &rs); - boost::function + boost::function delete_cb = boost::bind(&deleteState, _1, _2, &rs); ros::ServiceServer save_state_server = node.advertiseService("save_robot_state", save_cb);