kinematic_options.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014, SRI International
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 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: Acorn Pooley */
00036 
00037 #include <moveit/robot_interaction/kinematic_options.h>
00038 #include <boost/static_assert.hpp>
00039 #include <ros/console.h>
00040 
00041 robot_interaction::KinematicOptions::KinematicOptions()
00042 : timeout_seconds_(0.0) // 0.0 = use default timeout
00043 , max_attempts_(0)      // 0 = use default max attempts
00044 { }
00045 
00046 // This is intended to be called as a ModifyStateFunction to modify the state
00047 // maintained by a LockedRobotState in place.
00048 bool robot_interaction::KinematicOptions::setStateFromIK(
00049       robot_state::RobotState& state,
00050       const std::string& group,
00051       const std::string& tip,
00052       const geometry_msgs::Pose& pose) const
00053 {
00054   const robot_model::JointModelGroup *jmg = state.getJointModelGroup(group);
00055   if (!jmg)
00056   {
00057     ROS_ERROR("No getJointModelGroup('%s') found",group.c_str());
00058     return false;
00059   }
00060   bool result = state.setFromIK(jmg,
00061                             pose,
00062                             tip,
00063                             max_attempts_,
00064                             timeout_seconds_,
00065                             state_validity_callback_,
00066                             options_);
00067   state.update();
00068   return result;
00069 }
00070 
00071 
00072 void robot_interaction::KinematicOptions::setOptions(
00073       const KinematicOptions& source,
00074       OptionBitmask fields)
00075 {
00076   // This function is implemented with the O_FIELDS and QO_FIELDS macros to
00077   // ensure that any fields added to robot_interaction::KinematicOptions or
00078   // kinematics::KinematicsQueryOptions are also added here and to the
00079   // KinematicOptions::OptionBitmask enum.
00080 
00081   // This needs to represent all the fields in
00082   // robot_interaction::KinematicOptions except options_
00083   #define O_FIELDS(F) \
00084     F(double, timeout_seconds_, TIMEOUT) \
00085     F(unsigned int, max_attempts_, MAX_ATTEMPTS) \
00086     F(robot_state::GroupStateValidityCallbackFn, state_validity_callback_, \
00087                                               STATE_VALIDITY_CALLBACK)
00088 
00089   // This needs to represent all the fields in
00090   // kinematics::KinematicsQueryOptions
00091   #define QO_FIELDS(F) \
00092     F(bool, lock_redundant_joints, LOCK_REDUNDANT_JOINTS) \
00093     F(bool, return_approximate_solution, RETURN_APPROXIMATE_SOLUTION)
00094 
00095 
00096   // This structure should be identical to kinematics::KinematicsQueryOptions
00097   // This is only used in the BOOST_STATIC_ASSERT below.
00098   struct DummyKinematicsQueryOptions
00099   {
00100     #define F(type,member,enumval) type member;
00101     QO_FIELDS(F)
00102     #undef F
00103   };
00104   // This structure should be identical to robot_interaction::KinematicOptions
00105   // This is only used in the BOOST_STATIC_ASSERT below.
00106   struct DummyKinematicOptions
00107   {
00108     #define F(type,member,enumval) type member;
00109     O_FIELDS(F)
00110     #undef F
00111     DummyKinematicsQueryOptions options_;
00112   };
00113 
00114   // If these asserts fails it means that fields were added to
00115   // kinematics::KinematicsQueryOptions or robot_interaction::KinematicOptions
00116   // and not added to the O_FIELDS and QO_FIELDS definitions above. To fix add
00117   // any new fields to the definitions above.
00118   BOOST_STATIC_ASSERT(sizeof(kinematics::KinematicsQueryOptions) ==
00119                       sizeof(DummyKinematicsQueryOptions));
00120   BOOST_STATIC_ASSERT(sizeof(KinematicOptions) ==
00121                       sizeof(DummyKinematicOptions));
00122 
00123 
00124   // copy fields from other to this if its bit is set in fields
00125   #define F(type,member,enumval) \
00126           if (fields & KinematicOptions::enumval) \
00127             member = source.member;
00128   O_FIELDS(F)
00129   #undef F
00130 
00131   // copy fields from other.options_ to this.options_ if its bit is set in
00132   // fields
00133   #define F(type,member,enumval) \
00134           if (fields & KinematicOptions::enumval) \
00135             options_.member = source.options_.member;
00136   QO_FIELDS(F)
00137   #undef F
00138 }


robot_interaction
Author(s): Ioan Sucan
autogenerated on Wed Aug 26 2015 12:44:19