cartesian_path_service_capability.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include "cartesian_path_service_capability.h"
00038 #include <moveit/robot_state/conversions.h>
00039 #include <moveit/kinematic_constraints/utils.h>
00040 #include <moveit/collision_detection/collision_tools.h>
00041 #include <eigen_conversions/eigen_msg.h>
00042 #include <moveit/move_group/capability_names.h>
00043 #include <moveit/planning_pipeline/planning_pipeline.h>
00044 #include <moveit_msgs/DisplayTrajectory.h>
00045 
00046 move_group::MoveGroupCartesianPathService::MoveGroupCartesianPathService() :
00047   MoveGroupCapability("CartesianPathService"),
00048   display_computed_paths_(true)
00049 {
00050 }
00051 
00052 void move_group::MoveGroupCartesianPathService::initialize()
00053 {
00054   display_path_ = node_handle_.advertise<moveit_msgs::DisplayTrajectory>(planning_pipeline::PlanningPipeline::DISPLAY_PATH_TOPIC, 10, true);
00055   cartesian_path_service_ = root_node_handle_.advertiseService(CARTESIAN_PATH_SERVICE_NAME, &MoveGroupCartesianPathService::computeService, this);
00056 }
00057 
00058 namespace
00059 {
00060 bool isStateValid(const planning_scene::PlanningScene *planning_scene,
00061                   const kinematic_constraints::KinematicConstraintSet *constraint_set,
00062                   robot_state::JointStateGroup *group, const std::vector<double> &ik_solution)
00063 {
00064   group->setVariableValues(ik_solution);
00065   return (!planning_scene || !planning_scene->isStateColliding(*group->getRobotState(), group->getName())) &&
00066     (!constraint_set || constraint_set->decide(*group->getRobotState()).satisfied);
00067 }
00068 }
00069 
00070 bool move_group::MoveGroupCartesianPathService::computeService(moveit_msgs::GetCartesianPath::Request &req, moveit_msgs::GetCartesianPath::Response &res)
00071 {
00072   ROS_INFO("Received request to compute Cartesian path");
00073   context_->planning_scene_monitor_->updateFrameTransforms();
00074 
00075   robot_state::RobotState start_state = planning_scene_monitor::LockedPlanningSceneRO(context_->planning_scene_monitor_)->getCurrentState();
00076   robot_state::robotStateMsgToRobotState(req.start_state, start_state);
00077   if (robot_state::JointStateGroup *jsg = start_state.getJointStateGroup(req.group_name))
00078   {
00079     std::string link_name = req.link_name;
00080     if (link_name.empty() && !jsg->getJointModelGroup()->getLinkModelNames().empty())
00081       link_name = jsg->getJointModelGroup()->getLinkModelNames().back();
00082 
00083     bool ok = true;
00084     EigenSTL::vector_Affine3d waypoints(req.waypoints.size());
00085     const std::string &default_frame = context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
00086     bool no_transform = req.header.frame_id.empty() || req.header.frame_id == default_frame || req.header.frame_id == link_name;
00087 
00088     for (std::size_t i = 0 ; i < req.waypoints.size() ; ++i)
00089     {
00090       if (no_transform)
00091         tf::poseMsgToEigen(req.waypoints[i], waypoints[i]);
00092       else
00093       {
00094         geometry_msgs::PoseStamped p;
00095         p.header = req.header;
00096         p.pose = req.waypoints[i];
00097         if (performTransform(p, default_frame))
00098           tf::poseMsgToEigen(p.pose, waypoints[i]);
00099         else
00100         {
00101       ROS_ERROR("Error encountered transforming waypoints to frame '%s'", default_frame.c_str());
00102           ok = false;
00103           break;
00104         }
00105       }
00106     }
00107 
00108     if (ok)
00109     {
00110       if (req.max_step < std::numeric_limits<double>::epsilon())
00111       {
00112         ROS_ERROR("Maximum step to take between consecutive configrations along Cartesian path was not specified (this value needs to be > 0)");
00113         res.error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
00114       }
00115       else
00116       {
00117         if (waypoints.size() > 0)
00118         {
00119           robot_state::StateValidityCallbackFn constraint_fn;
00120           boost::scoped_ptr<planning_scene_monitor::LockedPlanningSceneRO> ls;
00121           boost::scoped_ptr<kinematic_constraints::KinematicConstraintSet> kset;
00122           if (req.avoid_collisions || !kinematic_constraints::isEmpty(req.path_constraints))
00123           {
00124             ls.reset(new planning_scene_monitor::LockedPlanningSceneRO(context_->planning_scene_monitor_));
00125             kset.reset(new kinematic_constraints::KinematicConstraintSet((*ls)->getRobotModel()));
00126             kset->add(req.path_constraints, (*ls)->getTransforms());
00127             constraint_fn = boost::bind(&isStateValid, req.avoid_collisions ? static_cast<const planning_scene::PlanningSceneConstPtr&>(*ls).get() : NULL, kset->empty() ? NULL : kset.get(), _1, _2);
00128           }
00129       bool global_frame = link_name != req.header.frame_id;
00130           ROS_INFO("Attempting to follow %u waypoints for link '%s' using a step of %lf m and jump threshold %lf (in %s reference frame)",
00131                    (unsigned int)waypoints.size(), link_name.c_str(), req.max_step, req.jump_threshold, global_frame ? "global" : "link");
00132           std::vector<boost::shared_ptr<robot_state::RobotState> > traj;
00133           res.fraction = jsg->computeCartesianPath(traj, link_name, waypoints, global_frame, req.max_step, req.jump_threshold, constraint_fn);
00134           robot_state::robotStateToRobotStateMsg(start_state, res.start_state);
00135 
00136           robot_trajectory::RobotTrajectory rt(context_->planning_scene_monitor_->getRobotModel(), req.group_name);
00137           for (std::size_t i = 0 ; i < traj.size() ; ++i)
00138             rt.addSuffixWayPoint(traj[i], 0.2); // \todo make 0.2 a param
00139           rt.getRobotTrajectoryMsg(res.solution);
00140       ROS_INFO("Computed Cartesian path with %u points (followed %lf%% of requested trajectory)", (unsigned int)traj.size(), res.fraction * 100.0);
00141       if (display_computed_paths_ && rt.getWayPointCount() > 0)
00142       {
00143         moveit_msgs::DisplayTrajectory disp;
00144         disp.model_id = context_->planning_scene_monitor_->getRobotModel()->getName();
00145         disp.trajectory.resize(1, res.solution);
00146         robot_state::robotStateToRobotStateMsg(rt.getFirstWayPoint(), disp.trajectory_start);
00147         display_path_.publish(disp);
00148       }
00149         }
00150         res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00151       }
00152     }
00153     else
00154       res.error_code.val = moveit_msgs::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
00155   }
00156   else
00157     res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
00158 
00159   return true;
00160 }
00161 
00162 #include <class_loader/class_loader.h>
00163 CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupCartesianPathService, move_group::MoveGroupCapability)


move_group
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:32:44