ros_api_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 // Robot state publishing
00047 #include <moveit/robot_state/conversions.h>
00048 #include <moveit_msgs/DisplayRobotState.h>
00049 
00050 // Kinematics
00051 #include <moveit_msgs/GetPositionIK.h>
00052 
00053 int main(int argc, char **argv)
00054 {
00055   ros::init (argc, argv, "right_arm_kinematics");
00056   ros::AsyncSpinner spinner(1);
00057   spinner.start();
00058 
00059   ros::NodeHandle node_handle;
00060 
00061   // Start a service client
00062   ros::ServiceClient service_client = node_handle.serviceClient<moveit_msgs::GetPositionIK> ("compute_ik");
00063   ros::Publisher robot_state_publisher = node_handle.advertise<moveit_msgs::DisplayRobotState>( "tutorial_robot_state", 1 );
00064 
00065   while(!service_client.exists())
00066   {
00067     ROS_INFO("Waiting for service");
00068     sleep(1.0);
00069   }
00070 
00071   moveit_msgs::GetPositionIK::Request service_request;
00072   moveit_msgs::GetPositionIK::Response service_response;
00073 
00074   service_request.ik_request.group_name = "left_arm";
00075   service_request.ik_request.pose_stamped.header.frame_id = "torso_lift_link";
00076   service_request.ik_request.pose_stamped.pose.position.x = 0.75;
00077   service_request.ik_request.pose_stamped.pose.position.y = 0.188;
00078   service_request.ik_request.pose_stamped.pose.position.z = 0.0;
00079 
00080   service_request.ik_request.pose_stamped.pose.orientation.x = 0.0;
00081   service_request.ik_request.pose_stamped.pose.orientation.y = 0.0;
00082   service_request.ik_request.pose_stamped.pose.orientation.z = 0.0;
00083   service_request.ik_request.pose_stamped.pose.orientation.w = 1.0;
00084 
00085   /* Call the service */
00086   service_client.call(service_request, service_response);
00087   ROS_INFO_STREAM("Result: " << ((service_response.error_code.val == service_response.error_code.SUCCESS) ? "True " : "False ") << service_response.error_code.val);
00088 
00089   /* Filling in a seed state */
00090   robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
00091   robot_model::RobotModelPtr kinematic_model = robot_model_loader.getModel();
00092   robot_state::RobotStatePtr kinematic_state(new robot_state::RobotState(kinematic_model));
00093   robot_state::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup("left_arm");
00094 
00095   /* Get the names of the joints in the right_arm*/
00096   service_request.ik_request.robot_state.joint_state.name = joint_state_group->getJointModelGroup()->getJointModelNames();
00097 
00098   /* Get the joint values and put them into the message, this is where you could put in your own set of values as well.*/
00099   joint_state_group->setToRandomValues();
00100   joint_state_group->getVariableValues(service_request.ik_request.robot_state.joint_state.position);
00101 
00102   /* Call the service again*/
00103   service_client.call(service_request, service_response);
00104   ROS_INFO_STREAM("Result: " << ((service_response.error_code.val == service_response.error_code.SUCCESS) ? "True " : "False ") << service_response.error_code.val);
00105 
00106   /* Check for collisions*/
00107   service_request.ik_request.avoid_collisions = true;
00108 
00109   /* Call the service again*/
00110   service_client.call(service_request, service_response);
00111 
00112   ROS_INFO_STREAM("Result: " << ((service_response.error_code.val == service_response.error_code.SUCCESS) ? "True " : "False ") << service_response.error_code.val);
00113 
00114   /* Visualize the result*/
00115   moveit_msgs::DisplayRobotState msg;
00116   joint_state_group->setVariableValues(service_response.solution.joint_state);
00117   robot_state::robotStateToRobotStateMsg(*kinematic_state, msg.state);
00118   robot_state_publisher.publish(msg);
00119 
00120   //Sleep to let the message go through
00121   ros::Duration(2.0).sleep();
00122 
00123   ros::shutdown();
00124   return 0;
00125 }


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