collision_proximity_planner_plugin.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, 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 
00037 #include <collision_proximity_planner/collision_proximity_planner_plugin.h>
00038 #include <pluginlib/class_list_macros.h>
00039 
00040 PLUGINLIB_DECLARE_CLASS(collision_proximity_planner,CollisionProximityPlannerPlugin,collision_proximity_planner::CollisionProximityPlannerPlugin, motion_planning_state_refinement::MotionPlanningStateRefinement)
00041 
00042 namespace collision_proximity_planner 
00043 {
00044 CollisionProximityPlannerPlugin::CollisionProximityPlannerPlugin()
00045 {
00046 }
00047 
00048 bool CollisionProximityPlannerPlugin::setGroupName(const std::string &group_name)
00049 {
00050   return(planner_.initialize(group_name));
00051 }
00052 
00053 bool CollisionProximityPlannerPlugin::refineState(const arm_navigation_msgs::RobotState &robot_state,
00054                                                   const arm_navigation_msgs::Constraints &constraints,
00055                                                   arm_navigation_msgs::RobotState &group_state)
00056 {
00057   arm_navigation_msgs::RobotTrajectory robot_trajectory;
00058   arm_navigation_msgs::RobotState current_state = robot_state;
00059   planner_.fillInGroupState(current_state,group_state);
00060   bool solution_found = planner_.findPathToFreeState(current_state,robot_trajectory);
00061   if(!robot_trajectory.joint_trajectory.points.empty())
00062   {
00063     group_state.joint_state.header = robot_trajectory.joint_trajectory.header;
00064     group_state.joint_state.position = robot_trajectory.joint_trajectory.points.back().positions;
00065     group_state.joint_state.name = robot_trajectory.joint_trajectory.joint_names;
00066   }
00067   return solution_found;
00068 }
00069 
00070 bool CollisionProximityPlannerPlugin::setRobotState(const arm_navigation_msgs::RobotState &robot_state)
00071 {
00072   return planner_.setRobotState(robot_state);
00073 }
00074 
00075 bool CollisionProximityPlannerPlugin::setGroupState(const arm_navigation_msgs::RobotState &group_state)
00076 {
00077   return planner_.setGroupState(group_state);
00078 }
00079 
00080 bool CollisionProximityPlannerPlugin::setConstraints(const arm_navigation_msgs::Constraints &constraints)
00081 {
00082   return true;
00083 }
00084 
00085 bool CollisionProximityPlannerPlugin::refineState(arm_navigation_msgs::RobotState &group_state,
00086                                                   arm_navigation_msgs::RobotTrajectory &robot_trajectory)
00087 {
00088   return planner_.refineState(group_state,robot_trajectory);
00089 }
00090 
00091 void CollisionProximityPlannerPlugin::getStateGradient(const arm_navigation_msgs::RobotState &group_state,
00092                                                        double &distance,
00093                                                        arm_navigation_msgs::RobotState &gradient)
00094 {
00095   planner_.getStateGradient(group_state,distance,gradient);
00096 }
00097  
00098 void CollisionProximityPlannerPlugin::clear()
00099 {
00100   planner_.clear();
00101 }
00102 
00103 }


collision_proximity_planner
Author(s): Sachin Chitta
autogenerated on Thu Dec 12 2013 11:09:38