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

Port moveit_msgs services #29

Merged
merged 1 commit into from
Feb 27, 2019
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
Original file line number Diff line number Diff line change
Expand Up @@ -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<ros::ServiceClient>(
nonprivate_handle.serviceClient<moveit_msgs::GetPositionIK>(ik_service_name));
nonprivate_handle.serviceClient<moveit_msgs::srv::GetPositionIK>(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());
Expand Down Expand Up @@ -271,7 +271,7 @@ bool SrvKinematicsPlugin::searchPositionIK(const std::vector<geometry_msgs::Pose
}

// Create the service message
moveit_msgs::GetPositionIK ik_srv;
moveit_msgs::srv::GetPositionIK ik_srv;
ik_srv.request.ik_request.avoid_collisions = true;
ik_srv.request.ik_request.group_name = getGroupName();

Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/ompl/ompl_interface/src/ompl_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class OMPLPlannerService
}
}

bool computePlan(moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::GetMotionPlan::Response& res)
bool computePlan(moveit_msgs::srv::GetMotionPlan::Request& req, moveit_msgs::srv::GetMotionPlan::Response& res)
{
ROS_INFO("Received new planning request...");
if (debug_)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -211,7 +211,7 @@ class EnvironmentChain3D : public DiscreteSpaceInformation
virtual bool AreEquivalent(int StateID1, int StateID2);

bool setupForMotionPlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
const moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::GetMotionPlan::Response& res,
const moveit_msgs::srv::GetMotionPlan::Request& req, moveit_msgs::srv::GetMotionPlan::Response& res,
const PlanningParameters& params);

const EnvChain3DPlanningData& getPlanningData() const
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class SBPLInterface
}

bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
const moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::GetMotionPlan::Response& res,
const moveit_msgs::srv::GetMotionPlan::Request& req, moveit_msgs::srv::GetMotionPlan::Response& res,
const PlanningParameters& params) const;

const PlanningStatistics& getLastPlanningStatistics() const
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class SBPLMetaInterface
}

bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
const moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::GetMotionPlan::Response& res);
const moveit_msgs::srv::GetMotionPlan::Request& req, moveit_msgs::srv::GetMotionPlan::Response& res);

const PlanningStatistics& getLastPlanningStatistics() const
{
Expand All @@ -61,7 +61,7 @@ class SBPLMetaInterface

protected:
void runSolver(bool use_first, const planning_scene::PlanningSceneConstPtr& planning_scene,
const moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::GetMotionPlan::Response& res,
const moveit_msgs::srv::GetMotionPlan::Request& req, moveit_msgs::srv::GetMotionPlan::Response& res,
const PlanningParameters& params);

boost::mutex planner_done_mutex_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -424,8 +424,8 @@ void EnvironmentChain3D::SetAllPreds(CMDPSTATE* state)
/////////////////////////////////////////////////////////////////////////////

bool EnvironmentChain3D::setupForMotionPlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
const moveit_msgs::GetMotionPlan::Request& mreq,
moveit_msgs::GetMotionPlan::Response& mres,
const moveit_msgs::srv::GetMotionPlan::Request& mreq,
moveit_msgs::srv::GetMotionPlan::Response& mres,
const PlanningParameters& params)
{
std::cerr << "really here " << std::endl;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
namespace sbpl_interface
{
bool SBPLInterface::solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
const moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::GetMotionPlan::Response& res,
const moveit_msgs::srv::GetMotionPlan::Request& req, moveit_msgs::srv::GetMotionPlan::Response& res,
const PlanningParameters& params) const
{
res.trajectory.joint_trajectory.points.clear();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ SBPLMetaInterface::SBPLMetaInterface(const planning_models::RobotModelConstPtr&
}

bool SBPLMetaInterface::solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
const moveit_msgs::GetMotionPlan::Request& req, moveit_msgs::GetMotionPlan::Response& res)
const moveit_msgs::srv::GetMotionPlan::Request& req, moveit_msgs::srv::GetMotionPlan::Response& res)
{
first_ok_ = false;
first_done_ = false;
Expand All @@ -56,7 +56,7 @@ bool SBPLMetaInterface::solve(const planning_scene::PlanningSceneConstPtr& plann
param_bfs.use_bfs_ = true;
PlanningParameters param_no_bfs;
param_no_bfs.use_bfs_ = false;
moveit_msgs::GetMotionPlan::Response res1, res2;
moveit_msgs::srv::GetMotionPlan::Response res1, res2;
boost::thread thread1(boost::bind(&SBPLMetaInterface::runSolver, this, true, boost::cref(planning_scene),
boost::cref(req), boost::ref(res1), param_bfs));
boost::thread thread2(boost::bind(&SBPLMetaInterface::runSolver, this, false, boost::cref(planning_scene),
Expand Down Expand Up @@ -146,8 +146,8 @@ bool SBPLMetaInterface::solve(const planning_scene::PlanningSceneConstPtr& plann
}

void SBPLMetaInterface::runSolver(bool use_first, const planning_scene::PlanningSceneConstPtr& planning_scene,
const moveit_msgs::GetMotionPlan::Request& req,
moveit_msgs::GetMotionPlan::Response& res, const PlanningParameters& params)
const moveit_msgs::srv::GetMotionPlan::Request& req,
moveit_msgs::srv::GetMotionPlan::Response& res, const PlanningParameters& params)
{
try
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class SBPLMetaPlanner : public planning_interface::Planner
sbpl_meta_interface_.reset(new sbpl_interface::SBPLMetaInterface(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
Expand All @@ -63,16 +63,16 @@ class SBPLMetaPlanner : 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
{
bool solve_ok = sbpl_meta_interface_->solve(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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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;
Expand All @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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_)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<moveit_msgs::ExecuteKnownTrajectory::Request, moveit_msgs::ExecuteKnownTrajectory::Response>(
ops.template init<moveit_msgs::srv::ExecuteKnownTrajectory::Request, moveit_msgs::srv::ExecuteKnownTrajectory::Response>(
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_)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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();

Expand Down Expand Up @@ -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())
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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...
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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)
Expand Down Expand Up @@ -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())
Expand Down
Loading