state_display_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: Acorn Pooley
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 // PI
00051 #include <boost/math/constants/constants.hpp>
00052 
00053 
00054 // This code is described in the RobotStateDisplay tutorial here:
00055 //    http://moveit.ros.org/wiki/index.php/Groovy/RobotStateDisplay/C%2B%2B_API
00056 
00057 
00058 int main(int argc, char **argv)
00059 {
00060   ros::init (argc, argv, "state_display_tutorial");
00061 
00062   /* Needed for ROS_INFO commands to work */
00063   ros::AsyncSpinner spinner(1);
00064   spinner.start();
00065 
00066   /* Load the robot model */
00067   robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
00068 
00069   /* Get a shared pointer to the model */
00070   robot_model::RobotModelPtr kinematic_model = robot_model_loader.getModel();
00071 
00072   /* Create a kinematic state - this represents the configuration for the robot represented by kinematic_model */
00073   robot_state::RobotStatePtr kinematic_state(new robot_state::RobotState(kinematic_model));
00074 
00075   /* Get the configuration for the joints in the right arm of the PR2*/
00076   robot_state::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup("right_arm");
00077 
00078 
00079 
00080   /* PUBLISH RANDOM ARM POSITIONS */
00081   ros::NodeHandle nh;
00082   ros::Publisher robot_state_publisher = nh.advertise<moveit_msgs::DisplayRobotState>( "tutorial_robot_state", 1 );
00083 
00084   /* loop at 1 Hz */
00085   ros::Rate loop_rate(1);
00086 
00087   for (int cnt=0; cnt<5 && ros::ok(); cnt++)
00088   {
00089     joint_state_group->setToRandomValues();
00090 
00091     /* get a robot state message describing the pose in kinematic_state */
00092     moveit_msgs::DisplayRobotState msg;
00093     robot_state::robotStateToRobotStateMsg(*kinematic_state, msg.state);
00094 
00095     /* send the message to the RobotState display */
00096     robot_state_publisher.publish( msg );
00097 
00098     /* let ROS send the message, then wait a while */
00099     ros::spinOnce();
00100     loop_rate.sleep();
00101   }
00102 
00103 
00104 
00105   /* POSITION END EFFECTOR AT SPECIFIC LOCATIONS */
00106 
00107   /* Find the default pose for the end effector */
00108   kinematic_state->setToDefaultValues();
00109 
00110   const Eigen::Affine3d end_effector_default_pose =
00111       kinematic_state->getLinkState("r_wrist_roll_link")->getGlobalLinkTransform();
00112 
00113   const double PI = boost::math::constants::pi<double>();
00114   const double RADIUS = 0.1;
00115 
00116   for (double angle=0; angle<=2*PI && ros::ok(); angle+=2*PI/20)
00117   {
00118 
00119     /* calculate a position for the end effector */
00120     Eigen::Affine3d end_effector_pose =
00121       Eigen::Translation3d(RADIUS * cos(angle), RADIUS * sin(angle), 0.0) * end_effector_default_pose;
00122 
00123     ROS_INFO_STREAM("End effector position:\n" << end_effector_pose.translation());
00124 
00125     /* use IK to get joint angles satisfyuing the calculated position */
00126     bool found_ik = joint_state_group->setFromIK(end_effector_pose, 10, 0.1);
00127     if (!found_ik)
00128     {
00129       ROS_INFO_STREAM("Could not solve IK for pose\n" << end_effector_pose.translation());
00130       continue;
00131     }
00132 
00133     /* get a robot state message describing the pose in kinematic_state */
00134     moveit_msgs::DisplayRobotState msg;
00135     robot_state::robotStateToRobotStateMsg(*kinematic_state, msg.state);
00136 
00137     /* send the message to the RobotState display */
00138     robot_state_publisher.publish( msg );
00139 
00140     /* let ROS send the message, then wait a while */
00141     ros::spinOnce();
00142     loop_rate.sleep();
00143   }
00144 
00145   ros::shutdown();
00146   return 0;
00147 }


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