kinematic_model_tutorial.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2012, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of Willow Garage, Inc. nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Sachin Chitta
00036 *********************************************************************/
00037 
00038 #include <ros/ros.h>
00039 
00040 // MoveIt!
00041 #include <moveit/robot_model_loader/robot_model_loader.h>
00042 #include <moveit/robot_model/robot_model.h>
00043 #include <moveit/robot_state/robot_state.h>
00044 #include <moveit/robot_state/joint_state_group.h>
00045 
00046 int main(int argc, char **argv)
00047 {
00048   ros::init (argc, argv, "right_arm_kinematics");
00049   ros::AsyncSpinner spinner(1);
00050   spinner.start();
00051 
00052   /* Load the robot model */
00053   robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
00054 
00055   /* Get a shared pointer to the model */
00056   robot_model::RobotModelPtr kinematic_model = robot_model_loader.getModel();
00057 
00058   /* Get and print the name of the coordinate frame in which the transforms for this model are computed*/
00059   ROS_INFO("Model frame: %s", kinematic_model->getModelFrame().c_str());
00060 
00061   /* WORKING WITH THE KINEMATIC STATE */
00062   /* Create a kinematic state - this represents the configuration for the robot represented by kinematic_model */
00063   robot_state::RobotStatePtr kinematic_state(new robot_state::RobotState(kinematic_model));
00064 
00065   /* Set all joints in this state to their default values */
00066   kinematic_state->setToDefaultValues();
00067 
00068   /* Get the configuration for the joints in the right arm of the PR2*/
00069   robot_state::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup("right_arm");
00070 
00071   /* Get the names of the joints in the right_arm*/
00072   const std::vector<std::string> &joint_names = joint_state_group->getJointModelGroup()->getJointModelNames();
00073 
00074   /* Get the joint states for the right arm*/
00075   std::vector<double> joint_values;
00076   joint_state_group->getVariableValues(joint_values);
00077 
00078   /* Print joint names and values */
00079   for(std::size_t i = 0; i < joint_names.size(); ++i)
00080   {
00081     ROS_INFO("Joint %s: %f", joint_names[i].c_str(), joint_values[i]);
00082   }
00083 
00084   /* Set one joint in the right arm outside its joint limit */
00085   joint_values[0] = 1.57;
00086   joint_state_group->setVariableValues(joint_values);
00087 
00088   /* Check whether any joint is outside its joint limits */
00089   ROS_INFO_STREAM("Current state is " << (kinematic_state->satisfiesBounds() ? "valid" : "not valid"));
00090 
00091   /* Enforce the joint limits for this state and check again*/
00092   kinematic_state->enforceBounds();
00093   ROS_INFO_STREAM("Current state is " << (kinematic_state->satisfiesBounds() ? "valid" : "not valid"));
00094 
00095   /* FORWARD KINEMATICS */
00096   /* Compute FK for a set of random joint values*/
00097   joint_state_group->setToRandomValues();
00098   const Eigen::Affine3d &end_effector_state = joint_state_group->getRobotState()->getLinkState("r_wrist_roll_link")->getGlobalLinkTransform();
00099 
00100   /* Print end-effector pose. Remember that this is in the model frame */
00101   ROS_INFO_STREAM("Translation: " << end_effector_state.translation());
00102   ROS_INFO_STREAM("Rotation: " << end_effector_state.rotation());
00103 
00104   /* INVERSE KINEMATICS */
00105   /* Set joint state group to a set of random values*/
00106   joint_state_group->setToRandomValues();
00107 
00108   /* Do IK on the pose we just generated using forward kinematics
00109    * Here 10 is the number of random restart and 0.1 is the allowed time after
00110    * each restart
00111    */
00112   bool found_ik = joint_state_group->setFromIK(end_effector_state, 10, 0.1);
00113 
00114   /* Get and print the joint values */
00115   if (found_ik)
00116   {
00117     joint_state_group->getVariableValues(joint_values);
00118     for(std::size_t i=0; i < joint_names.size(); ++i)
00119     {
00120       ROS_INFO("Joint %s: %f", joint_names[i].c_str(), joint_values[i]);
00121     }
00122   }
00123   else
00124   {
00125     ROS_INFO("Did not find IK solution");
00126   }
00127 
00128   /* DIFFERENTIAL KINEMATICS */
00129   /* Get and print the Jacobian for the right arm*/
00130   Eigen::Vector3d reference_point_position(0.0,0.0,0.0);
00131   Eigen::MatrixXd jacobian;
00132   joint_state_group->getJacobian(joint_state_group->getJointModelGroup()->getLinkModelNames().back(),
00133                                  reference_point_position,
00134                                  jacobian);
00135   ROS_INFO_STREAM("Jacobian: " << jacobian);
00136 
00137   ros::shutdown();
00138   return 0;
00139 }


pr2_moveit_tutorials
Author(s): Sachin Chitta
autogenerated on Mon Oct 6 2014 11:15:31